greet_one.cpp
Go to the documentation of this file.
1 #include "ros/ros.h"
2 #include "xbot_talker/play.h"
3 #include "xbot_talker/chat.h"
4 #include "xbot_face/FaceResult.h"
5 #include <string.h>
6 
7 
8 using namespace std;
9 int detect_times = 0;
10 bool meet = false;
11 
14 
15 string kehu = "lyh";
16 string wenhou = "你好,刘银河";
17 
18 void faceCB(xbot_face::FaceResult msg){
19  if(meet)
20  {
21  return;
22  }
23 
24  if(msg.face_exist == false)
25  {
26  detect_times = 0;
27  return;
28  }
29 
30  if((msg.name == kehu)&&(msg.confidence>0.6))
31  {
32  detect_times+=1;
33 
34  }
35  else
36  {
37  detect_times = 0;
38  }
39 
40  if (detect_times>=5)
41  {
42  meet = true;
43  xbot_talker::play srv;
44  srv.request.mode = 1;
45  srv.request.tts_text = wenhou;
46 
47  if (playclient.call(srv))
48  {
49  //ROS_INFO("Result: %s", srv.response.result);
50  }
51  else
52  {
53  ROS_ERROR("Failed to call service play");
54  return;
55  }
56  xbot_talker::chat srv1;
57  srv1.request.start_chat = true;
58 
59  if(chatclient.call(srv1))
60  {
61  ROS_INFO("Result: %b", srv1.response.chat_success);
62  exit(0);
63  }
64  else
65  {
66  ROS_ERROR("Failed to call service play");
67  return;
68  }
69 
70  }
71 
72 }
73 
74 int main(int argc, char **argv)
75 {
76  ros::init(argc, argv, "play_client");
78 
79 
80  ros::Subscriber sub = n.subscribe("/xbot/face_result",1000, faceCB);
81  playclient = n.serviceClient<xbot_talker::play>("/play");
82  chatclient = n.serviceClient<xbot_talker::chat>("/chat");
83  ros::spin();
84 
85 
86 
87  return 0;
88 }
89 
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::ServiceClient chatclient
Definition: greet_one.cpp:13
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
Definition: greet_one.cpp:74
string wenhou
Definition: greet_one.cpp:16
bool meet
Definition: greet_one.cpp:10
#define ROS_INFO(...)
ros::ServiceClient playclient
Definition: greet_one.cpp:12
void faceCB(xbot_face::FaceResult msg)
Definition: greet_one.cpp:18
string kehu
Definition: greet_one.cpp:15
#define n
#define ROS_ERROR(...)
int detect_times
Definition: greet_one.cpp:9


xbot_navi
Author(s):
autogenerated on Sat Oct 10 2020 03:27:50