Public Member Functions | Private Member Functions | Private Attributes
explore::Explore Class Reference

A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment. More...

#include <explore.h>

List of all members.

Public Member Functions

void execute ()
 Runs whenever a new goal is sent to the move_base.
 Explore ()
 Constructor.
void spin ()
virtual ~Explore ()
 Destructor - Cleans up.

Private Member Functions

bool goalOnBlacklist (const geometry_msgs::PoseStamped &goal)
void makePlan ()
 Make a global plan.
bool mapCallback (nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
 Resets the costmaps to the static map outside a given window.
void publishGoal (const geometry_msgs::Pose &goal)
 Publish a goal to the visualizer.
void publishMap ()
 publish map
void reachedGoal (const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, geometry_msgs::PoseStamped frontier_goal)

Private Attributes

boost::mutex client_mutex_
bool close_loops_
bool done_exploring_
costmap_2d::Costmap2DROSexplore_costmap_ros_
ExploreFrontierexplorer_
std::vector
< geometry_msgs::PoseStamped > 
frontier_blacklist_
double gain_scale_
tf::Stamped< tf::Poseglobal_pose_
LoopClosureloop_closure_
ros::Publisher map_publisher_
ros::ServiceServer map_server_
ros::Publisher marker_array_publisher_
ros::Publisher marker_publisher_
actionlib::SimpleActionClient
< move_base_msgs::MoveBaseAction
move_base_client_
ros::NodeHandle node_
double orientation_scale_
navfn::NavfnROSplanner_
double planner_frequency_
double potential_scale_
geometry_msgs::PoseStamped prev_goal_
unsigned int prev_plan_size_
double progress_timeout_
std::string robot_base_frame_
tf::TransformListener tf_
double time_since_progress_
int visualize_

Detailed Description

A class adhering to the robot_actions::Action interface that moves the robot base to explore its environment.

Definition at line 61 of file explore.h.


Constructor & Destructor Documentation

Constructor.

Returns:

Definition at line 54 of file explore.cpp.

Destructor - Cleans up.

Definition at line 103 of file explore.cpp.


Member Function Documentation

Runs whenever a new goal is sent to the move_base.

Parameters:
goalThe goal to pursue
feedbackFeedback that the action gives to a higher-level monitor, in this case, the position of the robot
Returns:
The result of the execution, ie: Success, Preempted, Aborted, etc.

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.

Parameters:
goalThe 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.

Definition at line 340 of file explore.cpp.


Member Data Documentation

boost::mutex explore::Explore::client_mutex_ [private]

Definition at line 139 of file explore.h.

Definition at line 140 of file explore.h.

Definition at line 121 of file explore.h.

Definition at line 115 of file explore.h.

Definition at line 128 of file explore.h.

std::vector<geometry_msgs::PoseStamped> explore::Explore::frontier_blacklist_ [private]

Definition at line 134 of file explore.h.

Definition at line 138 of file explore.h.

Definition at line 130 of file explore.h.

Definition at line 133 of file explore.h.

Definition at line 125 of file explore.h.

Definition at line 126 of file explore.h.

Definition at line 124 of file explore.h.

Definition at line 123 of file explore.h.

Definition at line 117 of file explore.h.

Definition at line 113 of file explore.h.

Definition at line 138 of file explore.h.

Definition at line 119 of file explore.h.

Definition at line 131 of file explore.h.

Definition at line 138 of file explore.h.

geometry_msgs::PoseStamped explore::Explore::prev_goal_ [private]

Definition at line 135 of file explore.h.

unsigned int explore::Explore::prev_plan_size_ [private]

Definition at line 136 of file explore.h.

Definition at line 137 of file explore.h.

std::string explore::Explore::robot_base_frame_ [private]

Definition at line 120 of file explore.h.

Definition at line 114 of file explore.h.

Definition at line 137 of file explore.h.

Definition at line 132 of file explore.h.


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


explore
Author(s): Charles DuHadway (maintained by Benjamin Pitzer)
autogenerated on Sun Oct 5 2014 23:56:48