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::Costmap2DROS > | explore_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_ |
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.
|
inline |
Constructor for the server, sets up this node's ActionServer for exploration and ActionClient to move_base for robot movement.
name | Name for SimpleActionServer |
Definition at line 34 of file explore_server.cpp.
|
inlineprivate |
Done callback for the move_base client, checks for errors and aborts exploration task if necessary.
state | State from the move_base client |
result | Result from the move_base client |
Definition at line 241 of file explore_server.cpp.
|
inlineprivate |
Execute callback for actionserver, run after accepting a new goal.
goal | ActionGoal containing boundary of area to explore, and a valid centerpoint for the area. |
Definition at line 72 of file explore_server.cpp.
|
inlineprivate |
Feedback callback for the move_base client, republishes as feedback for the exploration server.
feedback | Feedback from the move_base client |
Definition at line 229 of file explore_server.cpp.
|
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.
|
private |
Definition at line 55 of file explore_server.cpp.
|
private |
Definition at line 57 of file explore_server.cpp.
|
private |
Definition at line 63 of file explore_server.cpp.
|
private |
Definition at line 58 of file explore_server.cpp.
|
private |
Definition at line 58 of file explore_server.cpp.
|
private |
Definition at line 64 of file explore_server.cpp.
|
private |
Definition at line 65 of file explore_server.cpp.
|
private |
Definition at line 62 of file explore_server.cpp.
|
private |
Definition at line 59 of file explore_server.cpp.
|
private |
Definition at line 52 of file explore_server.cpp.
|
private |
Definition at line 53 of file explore_server.cpp.
|
private |
Definition at line 60 of file explore_server.cpp.
|
private |
Definition at line 59 of file explore_server.cpp.
|
private |
Definition at line 54 of file explore_server.cpp.