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


xbot_face
Author(s):
autogenerated on Sat Oct 10 2020 03:27:46