Public Member Functions | Private Member Functions | Private Attributes | List of all members
frontier_exploration::FrontierExplorationServer Class Reference

Server for frontier exploration action, runs the state machine associated with a structured frontier exploration task and manages robot movement through move_base. More...

Public Member Functions

 FrontierExplorationServer (std::string name)
 Constructor for the server, sets up this node's ActionServer for exploration and ActionClient to move_base for robot movement. More...
 

Private Member Functions

void doneMovingCb (const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
 Done callback for the move_base client, checks for errors and aborts exploration task if necessary. More...
 
void executeCb (const frontier_exploration::ExploreTaskGoalConstPtr &goal)
 Execute callback for actionserver, run after accepting a new goal. More...
 
void feedbackMovingCb (const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
 Feedback callback for the move_base client, republishes as feedback for the exploration server. More...
 
void preemptCb ()
 Preempt callback for the server, cancels the current running goal and all associated movement actions. More...
 

Private Attributes

actionlib::SimpleActionServer< frontier_exploration::ExploreTaskAction > as_
 
boost::shared_ptr< costmap_2d::Costmap2DROSexplore_costmap_ros_
 
frontier_exploration::ExploreTaskFeedback feedback_
 
double frequency_
 
double goal_aliasing_
 
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > move_client_
 
move_base_msgs::MoveBaseGoal move_client_goal_
 
boost::mutex move_client_lock_
 
bool moving_
 
ros::NodeHandle nh_
 
ros::NodeHandle private_nh_
 
int retry_
 
bool success_
 
tf::TransformListener tf_listener_
 

Detailed Description

Server for frontier exploration action, runs the state machine associated with a structured frontier exploration task and manages robot movement through move_base.

Definition at line 25 of file explore_server.cpp.

Constructor & Destructor Documentation

frontier_exploration::FrontierExplorationServer::FrontierExplorationServer ( std::string  name)
inline

Constructor for the server, sets up this node's ActionServer for exploration and ActionClient to move_base for robot movement.

Parameters
nameName for SimpleActionServer

Definition at line 34 of file explore_server.cpp.

Member Function Documentation

void frontier_exploration::FrontierExplorationServer::doneMovingCb ( const actionlib::SimpleClientGoalState state,
const move_base_msgs::MoveBaseResultConstPtr &  result 
)
inlineprivate

Done callback for the move_base client, checks for errors and aborts exploration task if necessary.

Parameters
stateState from the move_base client
resultResult from the move_base client

Definition at line 241 of file explore_server.cpp.

void frontier_exploration::FrontierExplorationServer::executeCb ( const frontier_exploration::ExploreTaskGoalConstPtr &  goal)
inlineprivate

Execute callback for actionserver, run after accepting a new goal.

Parameters
goalActionGoal containing boundary of area to explore, and a valid centerpoint for the area.

Definition at line 72 of file explore_server.cpp.

void frontier_exploration::FrontierExplorationServer::feedbackMovingCb ( const move_base_msgs::MoveBaseFeedbackConstPtr &  feedback)
inlineprivate

Feedback callback for the move_base client, republishes as feedback for the exploration server.

Parameters
feedbackFeedback from the move_base client

Definition at line 229 of file explore_server.cpp.

void frontier_exploration::FrontierExplorationServer::preemptCb ( )
inlineprivate

Preempt callback for the server, cancels the current running goal and all associated movement actions.

Definition at line 213 of file explore_server.cpp.

Member Data Documentation

actionlib::SimpleActionServer<frontier_exploration::ExploreTaskAction> frontier_exploration::FrontierExplorationServer::as_
private

Definition at line 55 of file explore_server.cpp.

boost::shared_ptr<costmap_2d::Costmap2DROS> frontier_exploration::FrontierExplorationServer::explore_costmap_ros_
private

Definition at line 57 of file explore_server.cpp.

frontier_exploration::ExploreTaskFeedback frontier_exploration::FrontierExplorationServer::feedback_
private

Definition at line 63 of file explore_server.cpp.

double frontier_exploration::FrontierExplorationServer::frequency_
private

Definition at line 58 of file explore_server.cpp.

double frontier_exploration::FrontierExplorationServer::goal_aliasing_
private

Definition at line 58 of file explore_server.cpp.

actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> frontier_exploration::FrontierExplorationServer::move_client_
private

Definition at line 64 of file explore_server.cpp.

move_base_msgs::MoveBaseGoal frontier_exploration::FrontierExplorationServer::move_client_goal_
private

Definition at line 65 of file explore_server.cpp.

boost::mutex frontier_exploration::FrontierExplorationServer::move_client_lock_
private

Definition at line 62 of file explore_server.cpp.

bool frontier_exploration::FrontierExplorationServer::moving_
private

Definition at line 59 of file explore_server.cpp.

ros::NodeHandle frontier_exploration::FrontierExplorationServer::nh_
private

Definition at line 52 of file explore_server.cpp.

ros::NodeHandle frontier_exploration::FrontierExplorationServer::private_nh_
private

Definition at line 53 of file explore_server.cpp.

int frontier_exploration::FrontierExplorationServer::retry_
private

Definition at line 60 of file explore_server.cpp.

bool frontier_exploration::FrontierExplorationServer::success_
private

Definition at line 59 of file explore_server.cpp.

tf::TransformListener frontier_exploration::FrontierExplorationServer::tf_listener_
private

Definition at line 54 of file explore_server.cpp.


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


frontier_exploration
Author(s): Paul Bovbel
autogenerated on Mon Jun 10 2019 13:25:00