A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment. More...
#include <explore.h>
A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment.
explore::Explore::~Explore | ( | ) | [virtual] |
Destructor - Cleans up.
Definition at line 103 of file explore.cpp.
void explore::Explore::execute | ( | ) |
Runs whenever a new goal is sent to the move_base.
goal | The goal to pursue |
feedback | Feedback that the action gives to a higher-level monitor, in this case, the position of the robot |
Definition at line 315 of file explore.cpp.
bool explore::Explore::goalOnBlacklist | ( | const geometry_msgs::PoseStamped & | goal | ) | [private] |
Definition at line 285 of file explore.cpp.
void explore::Explore::makePlan | ( | ) | [private] |
Make a global plan.
Definition at line 204 of file explore.cpp.
bool explore::Explore::mapCallback | ( | nav_msgs::GetMap::Request & | req, |
nav_msgs::GetMap::Response & | res | ||
) | [private] |
Resets the costmaps to the static map outside a given window.
Definition at line 117 of file explore.cpp.
void explore::Explore::publishGoal | ( | const geometry_msgs::Pose & | goal | ) | [private] |
Publish a goal to the visualizer.
goal | The goal to visualize |
Definition at line 185 of file explore.cpp.
void explore::Explore::publishMap | ( | ) | [private] |
publish map
Definition at line 151 of file explore.cpp.
void explore::Explore::reachedGoal | ( | const actionlib::SimpleClientGoalState & | status, |
const move_base_msgs::MoveBaseResultConstPtr & | result, | ||
geometry_msgs::PoseStamped | frontier_goal | ||
) | [private] |
Definition at line 297 of file explore.cpp.
void explore::Explore::spin | ( | ) |
Definition at line 340 of file explore.cpp.
boost::mutex explore::Explore::client_mutex_ [private] |
bool explore::Explore::close_loops_ [private] |
bool explore::Explore::done_exploring_ [private] |
ExploreFrontier* explore::Explore::explorer_ [private] |
std::vector<geometry_msgs::PoseStamped> explore::Explore::frontier_blacklist_ [private] |
double explore::Explore::gain_scale_ [private] |
tf::Stamped<tf::Pose> explore::Explore::global_pose_ [private] |
LoopClosure* explore::Explore::loop_closure_ [private] |
ros::NodeHandle explore::Explore::node_ [private] |
double explore::Explore::orientation_scale_ [private] |
navfn::NavfnROS* explore::Explore::planner_ [private] |
double explore::Explore::planner_frequency_ [private] |
double explore::Explore::potential_scale_ [private] |
geometry_msgs::PoseStamped explore::Explore::prev_goal_ [private] |
unsigned int explore::Explore::prev_plan_size_ [private] |
double explore::Explore::progress_timeout_ [private] |
std::string explore::Explore::robot_base_frame_ [private] |
tf::TransformListener explore::Explore::tf_ [private] |
double explore::Explore::time_since_progress_ [private] |
int explore::Explore::visualize_ [private] |