00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #include <explore_2d/exploration.h>
00040 #include <move_base_msgs/MoveBaseAction.h>
00041 #include <actionlib/client/simple_action_client.h>
00042 #include <ros/ros.h>
00043 #include <boost/thread.hpp>
00044
00045 namespace explore_2d
00046 {
00047
00048 namespace nm=nav_msgs;
00049 namespace mbm=move_base_msgs;
00050 namespace al=actionlib;
00051 namespace gm=geometry_msgs;
00052 using std::string;
00053
00054 typedef actionlib::SimpleActionClient<mbm::MoveBaseAction> Client;
00055
00056 class ExploreNode
00057 {
00058 public:
00059 ExploreNode();
00060 void spin();
00061
00062 private:
00063
00064 void mapCallback (const nm::OccupancyGrid& map);
00065
00066 ros::NodeHandle nh_;
00067 boost::mutex mutex_;
00068
00069 const string global_frame_;
00070
00071 bool have_received_map_;
00072 bool initialized_;
00073 Explorer explorer_;
00074
00075 Client move_base_client_;
00076 ros::Subscriber map_sub_;
00077 };
00078
00079
00080 ExploreNode::ExploreNode() :
00081 global_frame_("/map"),
00082 have_received_map_(false), initialized_(false), explorer_(0.5),
00083 move_base_client_("move_base", true),
00084 map_sub_(nh_.subscribe("map", 10, &ExploreNode::mapCallback, this))
00085 {
00086 ros::Duration d(5.0);
00087 while (ros::ok()) {
00088 if (move_base_client_.waitForServer(d)) {
00089 ROS_INFO ("Connected to move_base server");
00090 break;
00091 }
00092 ROS_INFO ("Waiting for connection to move_base server");
00093 }
00094 initialized_ = true;
00095 }
00096
00097
00098 void ExploreNode::mapCallback (const nm::OccupancyGrid& map)
00099 {
00100 ros::Rate r(1.0);
00101 if (initialized_) {
00102 boost::mutex::scoped_lock l(mutex_);
00103 explorer_.updateOccupancyGrid(map);
00104 have_received_map_ = true;
00105 }
00106 }
00107
00108
00109 void ExploreNode::spin ()
00110 {
00111 ros::Rate r(1.0);
00112 while (ros::ok()) {
00113 ros::spinOnce();
00114
00115 gm::Pose goal_pose;
00116 {
00117 boost::mutex::scoped_lock l(mutex_);
00118 if (!have_received_map_) {
00119 ROS_INFO_THROTTLE(5.0, "Waiting for a map before sending goals");
00120 continue;
00121 }
00122 goal_pose = explorer_.nextNavGoal();
00123 }
00124
00125 mbm::MoveBaseGoal goal;
00126 goal.target_pose.header.frame_id = global_frame_;
00127 goal.target_pose.header.stamp = ros::Time::now();
00128 goal.target_pose.pose = goal_pose;
00129 move_base_client_.sendGoal(goal);
00130 ROS_INFO_STREAM_NAMED ("goals", "Sending goal " << goal_pose);
00131 while (ros::ok()) {
00132 al::SimpleClientGoalState state = move_base_client_.getState();
00133 if (state == al::SimpleClientGoalState::PENDING ||
00134 state == al::SimpleClientGoalState::ACTIVE) {
00135 r.sleep();
00136 continue;
00137 }
00138 else if (state == al::SimpleClientGoalState::SUCCEEDED ||
00139 state == al::SimpleClientGoalState::ABORTED) {
00140 ROS_INFO_STREAM_NAMED ("goals", "Goal finished with result " << state.toString());
00141 break;
00142
00143 }
00144 else {
00145 ROS_ERROR_STREAM ("Unexpected client state " << state.toString() << "; exiting");
00146 return;
00147 }
00148 }
00149 }
00150 }
00151
00152
00153
00154
00155 }
00156
00157
00158
00159 int main (int argc, char** argv)
00160 {
00161 ros::init(argc, argv, "explore");
00162 explore_2d::ExploreNode n;
00163 n.spin();
00164 return 0;
00165 }