pp_explorer.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2010, ISR University of Coimbra.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the ISR University of Coimbra nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Gonçalo Cabrita on 5/1/2011
00036 *********************************************************************/
00037 #include <ros/ros.h>
00038 #include <move_base_msgs/MoveBaseAction.h>
00039 #include <actionlib/client/simple_action_client.h>
00040 
00041 #include "PPExplorer.h"
00042 
00043 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00044 
00045 bool send_goal;
00046 bool goal_failed;
00047 
00048 void goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
00049 {
00050         ROS_INFO("PPExplorer Node - goalDoneCallback - Goal is complete.");
00051         // If the goal succeeded send a new one!
00052         if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) send_goal = true;
00053         // If it was aborted time to back up!
00054         if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) goal_failed = true;
00055 }
00056 
00057 void goalActiveCallback()
00058 {
00059         //ROS_INFO("PPExplorer - goalActiveCallback - Node Goal active! Hurray!");
00060 }
00061 
00062 void goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
00063 {
00064         //ROS_INFO("PPExplorer Node - goalFeedbackCallback - Getting feedback! How cool is that?");
00065 }
00066 
00067 void sendRobotToGoal(MoveBaseClient * ac, geometry_msgs::PoseStamped * robot_goal)
00068 {
00069         move_base_msgs::MoveBaseGoal goal;
00070                         
00071         goal.target_pose.header.frame_id = robot_goal->header.frame_id;
00072         goal.target_pose.header.stamp = robot_goal->header.stamp;
00073 
00074         goal.target_pose.pose.position.x = robot_goal->pose.position.x;
00075         goal.target_pose.pose.position.y = robot_goal->pose.position.y;
00076         goal.target_pose.pose.orientation = robot_goal->pose.orientation;
00077         
00078         ROS_INFO("Sending robot to %lf %lf", robot_goal->pose.position.x, robot_goal->pose.position.y);
00079 
00080         ac->sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00081 }
00082 
00083 int main(int argc, char **argv)
00084 {
00085         ros::init(argc, argv, "pp_explorer_node");
00086         
00087         ROS_INFO("ParticlePlumeExplorer for ROS v1.0");
00088 
00089         particle_plume::PPExplorer pp;
00090         
00091         // Tell the action client that we want to spin a thread by default
00092         MoveBaseClient ac("move_base", true);
00093         // Wait for the action server to come up
00094         ROS_INFO("PPExplorer Node -- Waiting for the move_base action server to come online...");
00095         bool ac_online = false;
00096         for(int i=0 ; i<3 ; i++)
00097         {
00098                 if(ac.waitForServer(ros::Duration(1.0)))
00099                 {
00100                         ac_online = true;
00101                         break;
00102                 }
00103         
00104                 ROS_INFO("PPExplorer Node -- Unable to find the move_base action server, retrying...");
00105         }
00106         if(!ac_online)
00107         {
00108                 ROS_FATAL("PPExplorer Node -- Forgot to launch move_base now did we?");
00109                 ROS_BREAK();
00110                 return(-1);
00111         }
00112         ROS_INFO("PPExplorer Node -- Found it!");
00113         
00114         ROS_INFO("PPExplorer Node -- Waiting for a map msg to arrive...");
00115         while(!pp.isReady())
00116         {
00117                 ros::spinOnce();
00118                 ros::Duration(0.5).sleep();
00119         }
00120         ROS_INFO("PPExplorer Node -- Got it!");
00121         
00122         geometry_msgs::PoseStamped robot_goal;
00123         
00124         send_goal = true;
00125         goal_failed = false;
00126         
00127         ros::Time start_time = ros::Time::now();
00128         
00129         ros::Rate r(1);
00130         while(ros::ok())
00131         {
00132                 if(send_goal)
00133                 {
00134                         send_goal = false;
00135                         if(pp.findYumiestSlice(&robot_goal))
00136                         {
00137                                 sendRobotToGoal(&ac, &robot_goal);
00138                         }
00139                         else if(pp.findClearing(&robot_goal))
00140                         {
00141                                 ROS_WARN("PPExplorer Node -- All slices were discarded! Re-locating the robot...");
00142                                 sendRobotToGoal(&ac, &robot_goal);
00143                         }
00144                         else
00145                         {
00146                                 ROS_INFO("PPExplorer Node -- Finished!");
00147                                 ros::Duration time_spent = ros::Time::now() - start_time;
00148                                 ROS_INFO("PPExplorer Node -- Took %lf seconds to complete the exploration! Got %lf%% of explored area!", time_spent.toSec(), pp.getExploredArea()*100.0);
00149                                 return(0);
00150                         }
00151                 }
00152                 
00153                 if(goal_failed)
00154                 {
00155                         goal_failed = false;
00156                         if(pp.nextYumiestSlice(&robot_goal))
00157                         {
00158                                 sendRobotToGoal(&ac, &robot_goal);
00159                         }
00160                         else if(pp.findClearing(&robot_goal))
00161                         {
00162                                 ROS_WARN("PPExplorer Node -- All slices turned out being bad goals! Re-locating the robot...");
00163                                 sendRobotToGoal(&ac, &robot_goal);
00164                         }
00165                         else
00166                         {
00167                                 ROS_INFO("PPExplorer Node -- Finished!");
00168                                 ros::Duration time_spent = ros::Time::now() - start_time;
00169                                 ROS_INFO("PPExplorer Node -- Took %lf seconds to complete the exploration! Got %lf%% of explored area!", time_spent.toSec(), pp.getExploredArea()*100.0);
00170                                 return(0);
00171                         }
00172                 }
00173                 
00174                 ros::spinOnce();
00175                 r.sleep();
00176         }
00177         
00178         return(0);
00179 }
00180 
00181 // EOF
00182 


pp_explorer
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:27:10