37 #ifndef NAV_EXPLORE_H_ 38 #define NAV_EXPLORE_H_ 46 #include <geometry_msgs/PoseStamped.h> 47 #include <move_base_msgs/MoveBaseAction.h> 49 #include <visualization_msgs/MarkerArray.h> 80 const std::vector<frontier_exploration::Frontier>& frontiers);
83 const move_base_msgs::MoveBaseResultConstPtr& result,
84 const geometry_msgs::Point& frontier_goal);
ros::Duration progress_timeout_
void visualizeFrontiers(const std::vector< frontier_exploration::Frontier > &frontiers)
Publish a frontiers as markers.
size_t last_markers_count_
double planner_frequency_
std::vector< geometry_msgs::Point > frontier_blacklist_
double orientation_scale_
void reachedGoal(const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, const geometry_msgs::Point &frontier_goal)
ros::Timer exploring_timer_
bool goalOnBlacklist(const geometry_msgs::Point &goal)
ros::NodeHandle private_nh_
geometry_msgs::Point prev_goal_
tf::TransformListener tf_listener_
A class adhering to the robot_actions::Action interface that moves the robot base to explore its envi...
frontier_exploration::FrontierSearch search_
void makePlan()
Make a global plan.
Thread-safe implementation of a frontier-search task for an input costmap.
ros::NodeHandle relative_nh_
ros::Publisher marker_array_publisher_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > move_base_client_
Costmap2DClient costmap_client_