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 ()
 Explore ()
void spin ()

Private Member Functions

bool goalOnBlacklist (const geometry_msgs::PoseStamped &goal)
void makePlan ()
 Make a global plan.
void publishFrontiers ()
 Publish a frontiers as markers.
void reachedGoal (const actionlib::SimpleClientGoalState &status, const move_base_msgs::MoveBaseResultConstPtr &result, const geometry_msgs::PoseStamped &frontier_goal)

Private Attributes

Costmap2DClient costmap_client_
bool done_exploring_
ExploreFrontier explorer_
std::vector
< geometry_msgs::PoseStamped > 
frontier_blacklist_
double gain_scale_
tf::Stamped< tf::Poseglobal_pose_
ros::Publisher marker_array_publisher_
actionlib::SimpleActionClient
< move_base_msgs::MoveBaseAction > 
move_base_client_
double orientation_scale_
navfn::NavfnROS planner_
double planner_frequency_
std::mutex planning_mutex_
double potential_scale_
geometry_msgs::PoseStamped prev_goal_
size_t prev_plan_size_
ros::NodeHandle private_nh_
double progress_timeout_
ros::NodeHandle relative_nh_
tf::TransformListener tf_listener_
double time_since_progress_
bool visualize_

Detailed Description

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

Definition at line 69 of file explore.h.


Constructor & Destructor Documentation

Definition at line 45 of file explore.cpp.


Member Function Documentation

Definition at line 186 of file explore.cpp.

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

Definition at line 157 of file explore.cpp.

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

Make a global plan.

Definition at line 75 of file explore.cpp.

Publish a frontiers as markers.

Definition at line 68 of file explore.cpp.

void explore::Explore::reachedGoal ( const actionlib::SimpleClientGoalState status,
const move_base_msgs::MoveBaseResultConstPtr &  result,
const geometry_msgs::PoseStamped &  frontier_goal 
) [private]

Definition at line 171 of file explore.cpp.

Definition at line 204 of file explore.cpp.


Member Data Documentation

Definition at line 100 of file explore.h.

Definition at line 113 of file explore.h.

Definition at line 103 of file explore.h.

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

Definition at line 108 of file explore.h.

Definition at line 112 of file explore.h.

Definition at line 106 of file explore.h.

Definition at line 97 of file explore.h.

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

Definition at line 102 of file explore.h.

Definition at line 112 of file explore.h.

Definition at line 101 of file explore.h.

Definition at line 107 of file explore.h.

std::mutex explore::Explore::planning_mutex_ [private]

Definition at line 104 of file explore.h.

Definition at line 112 of file explore.h.

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

Definition at line 109 of file explore.h.

Definition at line 110 of file explore.h.

Definition at line 95 of file explore.h.

Definition at line 111 of file explore.h.

Definition at line 96 of file explore.h.

Definition at line 98 of file explore.h.

Definition at line 111 of file explore.h.

Definition at line 114 of file explore.h.


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


explore
Author(s): Jiri Horner
autogenerated on Sun Mar 26 2017 03:48:06