demo.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 and Pedro Sousa on 17/11/2010
00036 *********************************************************************/
00037 #include <vector>
00038 #include <string>
00039 
00040 #include <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <move_base_msgs/MoveBaseAction.h>
00043 #include <actionlib/client/simple_action_client.h>
00044 #include <geometry_msgs/Pose2D.h>
00045 #include <lse_sensor_msgs/Nostril.h>
00046 #include <roomba_500_series/Battery.h>
00047 #include <geometry_msgs/Twist.h>
00048 #include <fctuc_open_day/Poses.h>
00049 
00050 typedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;
00051 
00052 roomba_500_series::Battery battery;
00053 std::vector<geometry_msgs::Pose2D> targets;
00054 std::vector<geometry_msgs::Pose2D>::iterator target;
00055 
00056 bool sendNewGoal;
00057 bool needToBackUp;
00058 
00059 void goalDoneCallback(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
00060 {
00061         ROS_INFO("Goal is complete.");
00062         // If the goal succeeded send a new one!
00063         if(state.state_ == actionlib::SimpleClientGoalState::SUCCEEDED) sendNewGoal = true;
00064         // If it was aborted time to back up!
00065         if(state.state_ == actionlib::SimpleClientGoalState::ABORTED) needToBackUp = true;
00066 }
00067 
00068 void goalActiveCallback()
00069 {
00070         ROS_INFO("Goal active! Hurray!");
00071 }
00072 
00073 void goalFeedbackCallback(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
00074 {
00075         //ROS_INFO("Getting feedback! How cool is that?");
00076 }
00077 
00078 void noseCallback(const lse_sensor_msgs::Nostril::ConstPtr& nose)
00079 {
00080         
00081 }
00082 
00083 void batteryCallback(const roomba_500_series::Battery::ConstPtr& batt)
00084 {
00085         battery.level = batt->level;
00086         battery.dock = batt->dock;
00087 }
00088 
00089 void posesCallback(const fctuc_open_day::Poses::ConstPtr& poses)
00090 {
00091         ROS_INFO("Got a new batch of poses!");
00092         targets = poses->poses;
00093         target = targets.begin();
00094 }
00095 
00096 int main(int argc, char** argv)
00097 {
00098         ros::init(argc, argv, "fctuc_open_day_demo");
00099 
00100         ROS_INFO("Welcome to FCTUC Open Day Demo!");
00101         
00102         ros::NodeHandle n;
00103         
00104         std::string tf_prefix;
00105         n.param<std::string>("tf_prefix", tf_prefix, "");
00106         
00107         ros::Publisher cmd_vel_pub  = n.advertise<geometry_msgs::Twist>("/cmd_vel", 20);
00108         
00109         ros::Subscriber nose_sub = n.subscribe("/nose", 20, noseCallback);
00110         ros::Subscriber batt_sub = n.subscribe("/battery", 20, batteryCallback);
00111         ros::Subscriber pose_sub = n.subscribe("/poses", 2, posesCallback);
00112         
00113         ros::Rate r(10);
00114         ROS_INFO("Waiting for the first batch of poses to be published...");
00115         while(targets.size()==0 && ros::ok())
00116         {
00117                 ros::spinOnce();
00118                 r.sleep();
00119         }
00120         ROS_INFO("Got it!");
00121         
00122         // Tell the action client that we want to spin a thread by default
00123         MoveBaseClient ac("move_base", true);
00124         // Wait for the action server to come up
00125         ROS_INFO("Waiting for the move_base action server to come online...");
00126         if(!ac.waitForServer(ros::Duration(5.0)))
00127         {
00128                 ROS_FATAL("Forgot to launch move_base now did we?");
00129                 ROS_BREAK();
00130         }
00131         ROS_INFO("Found it!");
00132         
00133         int backUpCounter = 0;
00134         sendNewGoal = true;
00135         needToBackUp = false;
00136         
00137         target = targets.begin();
00138         while(ros::ok())
00139         {       
00140                 // If we are trapped or we are recharged back up a lil bit
00141                 if(needToBackUp || (battery.level>80.0 && battery.dock))
00142                 {
00143                         needToBackUp = true;
00144                         sendNewGoal = false;
00145                         if(backUpCounter==0)
00146                         {
00147                                 ROS_INFO("The wall is too close! I need to do some backing up...");
00148                                 // Move the robot back...
00149                                 geometry_msgs::Twist cmd_vel;
00150                                 cmd_vel.linear.x = -0.05;
00151                                 cmd_vel.angular.z = 0.0;
00152                                 cmd_vel_pub.publish(cmd_vel);
00153                         }
00154                         
00155                         if(backUpCounter==40)
00156                         {
00157                                 // Turn the robot around...
00158                                 geometry_msgs::Twist cmd_vel;
00159                                 cmd_vel.linear.x = 0.0;
00160                                 cmd_vel.angular.z = 0.5;
00161                                 cmd_vel_pub.publish(cmd_vel);
00162                         }
00163                         
00164                         if(backUpCounter==100)
00165                         {
00166                                 // Stop the robot...
00167                                 geometry_msgs::Twist cmd_vel;
00168                                 cmd_vel.linear.x = 0.0;
00169                                 cmd_vel.angular.z = 0.0;
00170                                 cmd_vel_pub.publish(cmd_vel);
00171                                 
00172                                 ROS_INFO("Done backing up, now on with my life!");
00173                                 
00174                                 // Reset variables
00175                                 backUpCounter = 0;
00176                                 sendNewGoal = true;
00177                                 needToBackUp = false;
00178                         }
00179                         backUpCounter++;
00180                 }
00181         
00182                 if(sendNewGoal)
00183                 {
00184                         std::string frame_name = tf_prefix;
00185                         move_base_msgs::MoveBaseGoal goal;
00186                 
00187                         // Send a goal to the robot
00188                         goal.target_pose.header.frame_id = frame_name.append("/map");
00189                         goal.target_pose.header.stamp = ros::Time::now();
00190                 
00191                         // Send the next goal
00192                         goal.target_pose.pose.position.x = target->x;
00193                         goal.target_pose.pose.position.y = target->y;
00194                         goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(target->theta);
00195                         
00196                         target++;
00197                         if(target==targets.end()) target=targets.begin();
00198                         
00199                         sendNewGoal = false;
00200                         ac.sendGoal(goal, boost::bind(&goalDoneCallback, _1, _2), boost::bind(&goalActiveCallback), boost::bind(&goalFeedbackCallback, _1));
00201                 }
00202                 
00203                 // If you smell something do interactive stuff!
00204                 //if()
00205                 
00206                 ros::spinOnce();
00207                 r.sleep();
00208         }
00209 
00210         ROS_INFO("Exiting FCTUC Open Day Demo...");
00211 
00212         return 0;
00213 }


fctuc_open_day
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:28:35