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 #include <stdio.h>
00023 #include <vector>
00024 #include <sstream>
00025 #include <algorithm>
00026
00027 #include <ros/ros.h>
00028 #include "std_msgs/String.h"
00029 #include "std_msgs/UInt16.h"
00030
00031 using namespace std;
00032 #include "Dictionary.cpp"
00033
00034
00035 enum Command_id { SERIVCE_MODE_0 = 0,
00036 SERIVCE_MODE_2 = 1,
00037 SERIVCE_MODE_3 = 2,
00038 ACK_SERVICE = 3,
00039 STOP_SERVICE = 4,
00040 TALK_INTRO = 5,
00041 TALK_LIKE = 6,
00042 TALK_PLEASURE = 7,
00043 TALK_THANKS = 8
00044 };
00045
00046 Dictionary dict;
00047
00048
00049 void speech_callback(const std_msgs::String::ConstPtr& msg);
00050
00051
00052 ros::Publisher cmd_pub;
00053
00054 int main(int argc, char** argv) {
00055 ros::init(argc, argv, "command_matcher_node");
00056 ros::NodeHandle n("~");
00057
00058 ros::Subscriber speech_sub = n.subscribe<std_msgs::String>("/speech_recognition", 1000, speech_callback);
00059
00060
00061 cmd_pub = n.advertise<std_msgs::UInt16>("/cmd", 1000);
00062
00063
00064 string cmd;
00065 size_t i = 0;
00066 char par_name[8];
00067 snprintf(par_name, 8, "cmd_%03d", i);
00068 while(n.hasParam(par_name)) {
00069 n.param<std::string>(par_name, cmd, "default_value");
00070 dict.add_entry(cmd);
00071 i++;
00072 snprintf(par_name, 8, "cmd_%03d", i);
00073 }
00074
00075 ROS_INFO("number of dictionary entries: %d", dict.size());
00076
00077
00078 ros::Rate r(10);
00079 while(ros::ok()) {
00080
00081 ros::spinOnce();
00082 r.sleep();
00083 }
00084
00085 return 0;
00086 }
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096 void speech_callback(const std_msgs::String::ConstPtr& msg) {
00097 string data = msg->data;
00098
00099 transform(data.begin(), data.end(), data.begin(), ::tolower);
00100
00101 int res = dict.findBestMatch(data);
00102
00103 if(res >= 0) {
00104 std_msgs::UInt16 send_msg;
00105 send_msg.data = (uint16_t) res;
00106 cmd_pub.publish(send_msg);
00107 }
00108
00109
00110 ROS_INFO("%s matched to command ID %d", data.c_str(), res);
00111 }