Go to the documentation of this file.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 
00031 
00032 
00033 #include <ros/ros.h>
00034 #include <std_msgs/String.h>
00035 #include <vision_msgs/cop_answer.h>
00036 #include <nav_pcontroller/nav_actionActionGoal.h>
00037 #include <boost/thread.hpp>
00038 
00039 boost::mutex mutex;
00040 
00041 
00042 void speakCallback(const std_msgs::String::ConstPtr &st)
00043 {
00044   
00045   char test[4096];
00046   if((*st).data.length() > 4096)
00047      return;
00048   printf("Saying: %s\n", (*st).data.c_str());
00049   sprintf(test, "say \"%s\"", (*st).data.c_str());
00050   mutex.lock();
00051   system(test);
00052   mutex.unlock();
00053 }
00054 void speakCopCallback(const vision_msgs::cop_answer::ConstPtr &answer)
00055 {
00056   std::string st;
00057   if((*answer).error.length() > 0)
00058   {
00059     return;
00060      st = (*answer).error;
00061   }
00062   else
00063   {
00064       st = "I Found an object, it is a ";
00065       printf("Looking for C: %i\n", (int)(*answer).found_poses[0].classes[0].compare("Cluster"));
00066       if((*answer).found_poses[0].classes[0] == "Cluster"){
00067           printf("[Ignoring Cluster]\n");
00068           return;
00069       }
00070       st = st.append((*answer).found_poses[0].classes[0]).append(" ");
00071       if((*answer).found_poses[0].classes.size() > 1)
00072       {
00073         if((*answer).found_poses[0].classes[1] == "Cluster "){
00074           printf("[Ignoring Cluster]\n");
00075           return;
00076         }
00077         st = st.append((*answer).found_poses[0].classes[1]);
00078       }
00079   } 
00080   
00081    char test[4096];
00082   if(st.length() > 4096)
00083      return;
00084   printf("Saying: '%s'\n", st.c_str());
00085   sprintf(test, "say \"%s\"", st.c_str());
00086   mutex.lock();
00087   system(test);
00088   mutex.unlock();
00089 }
00090 
00091 void speakNavCallback(const nav_pcontroller::nav_actionActionGoal::ConstPtr &answer)
00092 {
00093   std::string st;
00094   if((*answer).goal.target_lo.data==101)
00095      st = "  I am Going to the Table.      ";
00096   else if((*answer).goal.target_lo.data==100)
00097   {
00098       st = " I am  Going to the second Table.    ";
00099   
00100   }
00101   else
00102   {
00103     return;
00104   }
00105   
00106    char test[4096];
00107   if(st.length() > 4096)
00108      return;
00109   printf("Saying: %s\n", st.c_str());
00110   sprintf(test, "say \"%s\"", st.c_str());
00111    mutex.lock();
00112   system(test);
00113   mutex.unlock();
00114 }
00115 
00116 
00117 
00118 
00119 
00120 
00121 
00122 
00123 
00124 
00125 
00126 
00127 
00128 
00129 
00130 
00131 
00132 
00133 
00134 
00135 
00136 
00137 
00138 int main(int argc, char *argv[])
00139 {
00140   ros::init(argc, argv, "espeak") ;
00141   ros::NodeHandle n;
00142   ros::Subscriber sub = n.subscribe("/espeak/wordstosay", 1, &speakCallback);
00143   ros::Subscriber sub2 = n.subscribe("/kipla/cop_reply", 1, &speakCopCallback);
00144   ros::Subscriber sub3 = n.subscribe("/nav_pcontroller/nav_action/goal", 1, &speakNavCallback);
00145   
00146   ros::spin();
00147   return 0;
00148 }
00149 
00150 
00151 
00152 
00153