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

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

Private Member Functions

void getRobotPose (std::string frame, tf::Stamped< tf::Pose > &pose)
 Get the current pose of the robot in the specified frame.
bool goalOnBlacklist (const geometry_msgs::PoseStamped &goal)
bool isDone (explore_hrl::isDone_srv::Request &req, explore_hrl::isDone_srv::Response &res)
 ROS service handler to determine if explorer done exploring.
bool isRepeatGoal (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 done_exploring_
costmap_2d::Costmap2DROS * explore_costmap_ros_
ExploreFrontierexplorer_
std::vector
< geometry_msgs::PoseStamped > 
frontier_blacklist_
double gain_scale_
tf::Stamped< tf::Poseglobal_pose_
geometry_msgs::PoseStamped goal_pose_last_
bool goal_pose_last_defined_
double graph_update_frequency_
ros::ServiceServer isDone_srv_
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::NavfnROS * planner_
double potential_scale_
bool preempt_
std::string robot_base_frame_
tf::TransformListener tf_
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 62 of file explore.h.


Constructor & Destructor Documentation

Constructor.

Returns:

Definition at line 56 of file explore.cpp.

Destructor - Cleans up.

Definition at line 112 of file explore.cpp.


Member Function Documentation

Definition at line 517 of file explore.cpp.

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 443 of file explore.cpp.

void explore::Explore::getRobotPose ( std::string  frame,
tf::Stamped< tf::Pose > &  pose 
) [private]

Get the current pose of the robot in the specified frame.

Parameters:
frameThe frame to get the pose in
poseThe pose returned

Definition at line 261 of file explore.cpp.

bool explore::Explore::goalOnBlacklist ( const geometry_msgs::PoseStamped &  goal) [private]

Definition at line 415 of file explore.cpp.

bool explore::Explore::isDone ( explore_hrl::isDone_srv::Request &  req,
explore_hrl::isDone_srv::Response &  res 
) [private]

ROS service handler to determine if explorer done exploring.

Definition at line 154 of file explore.cpp.

bool explore::Explore::isRepeatGoal ( const geometry_msgs::PoseStamped &  goal) [private]

Definition at line 381 of file explore.cpp.

void explore::Explore::makePlan ( ) [private]

Make a global plan.

Definition at line 284 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 160 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 242 of file explore.cpp.

void explore::Explore::publishMap ( ) [private]

publish map

Definition at line 200 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 427 of file explore.cpp.

Definition at line 512 of file explore.cpp.

Definition at line 504 of file explore.cpp.


Member Data Documentation

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

Definition at line 162 of file explore.h.

Definition at line 146 of file explore.h.

costmap_2d::Costmap2DROS* explore::Explore::explore_costmap_ros_ [private]

Definition at line 137 of file explore.h.

Definition at line 154 of file explore.h.

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

Definition at line 160 of file explore.h.

Definition at line 161 of file explore.h.

Definition at line 156 of file explore.h.

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

Definition at line 139 of file explore.h.

Definition at line 140 of file explore.h.

Definition at line 157 of file explore.h.

Definition at line 135 of file explore.h.

Definition at line 159 of file explore.h.

Definition at line 151 of file explore.h.

Definition at line 152 of file explore.h.

Definition at line 150 of file explore.h.

Definition at line 149 of file explore.h.

actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> explore::Explore::move_base_client_ [private]

Definition at line 142 of file explore.h.

Definition at line 134 of file explore.h.

Definition at line 161 of file explore.h.

navfn::NavfnROS* explore::Explore::planner_ [private]

Definition at line 144 of file explore.h.

Definition at line 161 of file explore.h.

Definition at line 147 of file explore.h.

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

Definition at line 145 of file explore.h.

Definition at line 136 of file explore.h.

Definition at line 158 of file explore.h.


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


explore_hrl
Author(s): Travis Deyle
autogenerated on Wed Nov 27 2013 11:48:01