A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment. More...
#include <explore.h>
Public Member Functions | |
| Explore () | |
| void | start () |
| void | stop () |
| ~Explore () | |
Private Member Functions | |
| bool | goalOnBlacklist (const geometry_msgs::Point &goal) |
| void | makePlan () |
| Make a global plan. More... | |
| void | reachedGoal (const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, const geometry_msgs::Point &frontier_goal) |
| void | visualizeFrontiers (const std::vector< frontier_exploration::Frontier > &frontiers) |
| Publish a frontiers as markers. More... | |
Private Attributes | |
| Costmap2DClient | costmap_client_ |
| ros::Timer | exploring_timer_ |
| std::vector< geometry_msgs::Point > | frontier_blacklist_ |
| double | gain_scale_ |
| size_t | last_markers_count_ |
| ros::Time | last_progress_ |
| ros::Publisher | marker_array_publisher_ |
| actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > | move_base_client_ |
| ros::Timer | oneshot_ |
| double | orientation_scale_ |
| double | planner_frequency_ |
| double | potential_scale_ |
| double | prev_distance_ |
| geometry_msgs::Point | prev_goal_ |
| ros::NodeHandle | private_nh_ |
| ros::Duration | progress_timeout_ |
| ros::NodeHandle | relative_nh_ |
| frontier_exploration::FrontierSearch | search_ |
| tf::TransformListener | tf_listener_ |
| bool | visualize_ |
A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment.
| explore::Explore::Explore | ( | ) |
Definition at line 53 of file explore.cpp.
| explore::Explore::~Explore | ( | ) |
Definition at line 90 of file explore.cpp.
|
private |
Definition at line 247 of file explore.cpp.
|
private |
Make a global plan.
Definition at line 179 of file explore.cpp.
|
private |
Definition at line 264 of file explore.cpp.
| void explore::Explore::start | ( | ) |
Definition at line 283 of file explore.cpp.
| void explore::Explore::stop | ( | ) |
Definition at line 288 of file explore.cpp.
|
private |
Publish a frontiers as markers.
Definition at line 95 of file explore.cpp.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |