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 | |
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_ |
ExploreFrontier * | explorer_ |
std::vector < geometry_msgs::PoseStamped > | frontier_blacklist_ |
double | gain_scale_ |
tf::Stamped< tf::Pose > | global_pose_ |
geometry_msgs::PoseStamped | goal_pose_last_ |
bool | goal_pose_last_defined_ |
double | graph_update_frequency_ |
ros::ServiceServer | isDone_srv_ |
LoopClosure * | loop_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_ |
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 112 of file explore.cpp.
Definition at line 517 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 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.
frame | The frame to get the pose in |
pose | The 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.
goal | The 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.
void explore::Explore::setPreemptFlag | ( | bool | state | ) |
Definition at line 512 of file explore.cpp.
void explore::Explore::spin | ( | ) |
Definition at line 504 of file explore.cpp.
boost::mutex explore::Explore::client_mutex_ [private] |
bool explore::Explore::done_exploring_ [private] |
costmap_2d::Costmap2DROS* explore::Explore::explore_costmap_ros_ [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] |
geometry_msgs::PoseStamped explore::Explore::goal_pose_last_ [private] |
double explore::Explore::graph_update_frequency_ [private] |
LoopClosure* explore::Explore::loop_closure_ [private] |
actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> explore::Explore::move_base_client_ [private] |
ros::NodeHandle explore::Explore::node_ [private] |
double explore::Explore::orientation_scale_ [private] |
navfn::NavfnROS* explore::Explore::planner_ [private] |
double explore::Explore::potential_scale_ [private] |
bool explore::Explore::preempt_ [private] |
std::string explore::Explore::robot_base_frame_ [private] |
tf::TransformListener explore::Explore::tf_ [private] |
int explore::Explore::visualize_ [private] |