test_hri.cpp
Go to the documentation of this file.
1 // Copyright 2021 PAL Robotics S.L.
2 //
3 // Redistribution and use in source and binary forms, with or without
4 // modification, are permitted provided that the following conditions are met:
5 //
6 // * Redistributions of source code must retain the above copyright
7 // notice, this list of conditions and the following disclaimer.
8 //
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 //
13 // * Neither the name of the PAL Robotics S.L. nor the names of its
14 // contributors may be used to endorse or promote products derived from
15 // this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 // POSSIBILITY OF SUCH DAMAGE.
28 
29 #include <gtest/gtest.h>
30 #include <gmock/gmock.h>
31 #include <hri/hri.h>
32 #include <ros/ros.h>
33 #include <thread>
34 #include <chrono>
35 #include <memory>
36 #include "hri/face.h"
37 #include "hri/person.h"
38 #include "hri/voice.h"
39 #include "hri_msgs/EngagementLevel.h"
40 #include "hri_msgs/IdsList.h"
41 #include "hri_msgs/LiveSpeech.h"
42 #include "hri_msgs/NormalizedRegionOfInterest2D.h"
43 #include "hri_msgs/SoftBiometrics.h"
44 #include "std_msgs/Float32.h"
45 #include "std_msgs/String.h"
46 #include "std_msgs/Bool.h"
48 #include <geometry_msgs/TransformStamped.h>
49 
50 using namespace std;
51 using namespace ros;
52 using namespace hri;
53 
54 // waiting time for the libhri callback to process their inputs
55 #define WAIT std::this_thread::sleep_for(std::chrono::milliseconds(50))
56 #define WAIT_LONG std::this_thread::sleep_for(std::chrono::milliseconds(100))
57 #define WAIT_DEBUG \
58  { \
59  WAIT; \
60  cout << "waiting..." << endl; \
61  }
62 
63 TEST(libhri, GetFaces)
64 {
65  NodeHandle nh;
66 
68  spinner.start();
69 
70  Publisher pub;
71 
72  {
73  HRIListener hri_listener;
74 
75  pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
76 
77  ASSERT_EQ(pub.getNumSubscribers(), 1U);
78 
79  ASSERT_EQ(hri_listener.getFaces().size(), 0);
80 
81  auto ids = hri_msgs::IdsList();
82 
83  ROS_INFO("[A]");
84  ids.ids = { "A" };
85  pub.publish(ids);
86  WAIT;
87  auto faces = hri_listener.getFaces();
88  EXPECT_EQ(faces.size(), 1U);
89  ASSERT_TRUE(faces.find("A") != faces.end());
90  EXPECT_TRUE(faces["A"].lock()->id() == "A");
91 
92  ROS_INFO("[A]");
93  pub.publish(ids);
94  WAIT;
95  EXPECT_EQ(hri_listener.getFaces().size(), 1U);
96 
97  ROS_INFO("[A,B]");
98  ids.ids = { "A", "B" };
99  pub.publish(ids);
100  WAIT;
101  faces = hri_listener.getFaces();
102  EXPECT_EQ(faces.size(), 2U);
103  EXPECT_TRUE(faces.find("A") != faces.end());
104  EXPECT_TRUE(faces.find("B") != faces.end());
105 
106  ROS_INFO("[A,B]");
107  pub.publish(ids);
108  WAIT;
109  EXPECT_EQ(hri_listener.getFaces().size(), 2U);
110 
111  ROS_INFO("[B]");
112  ids.ids = { "B" };
113  pub.publish(ids);
114  WAIT;
115  faces = hri_listener.getFaces();
116  EXPECT_EQ(faces.size(), 1U);
117  EXPECT_TRUE(faces.find("A") == faces.end());
118  ASSERT_TRUE(faces.find("B") != faces.end());
119 
120  weak_ptr<const Face> face_b = faces["B"];
121  EXPECT_FALSE(face_b.expired()); // face B exists!
122 
123  ROS_INFO("[]");
124  ids.ids = {};
125  pub.publish(ids);
126  WAIT;
127  EXPECT_EQ(hri_listener.getFaces().size(), 0U);
128 
129  EXPECT_TRUE(face_b.expired()); // face B does not exist anymore!
130  }
131 
132  EXPECT_EQ(pub.getNumSubscribers(), 0);
133  spinner.stop();
134 }
135 
136 TEST(libhri, GetFacesRoi)
137 {
138  NodeHandle nh;
139 
141  spinner.start();
142 
143  HRIListener hri_listener;
144 
145  auto pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
146 
147  auto pub_r1 = nh.advertise<hri_msgs::NormalizedRegionOfInterest2D>("/humans/faces/A/roi", 1, true); // /roi topic is latched
148  auto pub_r2 = nh.advertise<hri_msgs::NormalizedRegionOfInterest2D>("/humans/faces/B/roi", 1, true); // /roi topic is latched
149 
150  auto ids = hri_msgs::IdsList();
151 
152  ids.ids = { "A" };
153  pub.publish(ids);
154  WAIT;
155 
156  EXPECT_EQ(pub_r1.getNumSubscribers(), 1U)
157  << "Face A should have subscribed to /humans/faces/A/roi";
158 
159 
160  ids.ids = { "B" };
161  pub.publish(ids);
162  WAIT;
163 
164  EXPECT_EQ(pub_r1.getNumSubscribers(), 0U)
165  << "Face A is deleted. No one should be subscribed to /humans/faces/A/roi anymore";
166  EXPECT_EQ(pub_r2.getNumSubscribers(), 1U)
167  << "Face B should have subscribed to /humans/faces/B/roi";
168 
169 
170  auto faces = hri_listener.getFaces();
171  ASSERT_FALSE(faces["B"].expired()); // face B still exists!
172 
173  auto roi = hri_msgs::NormalizedRegionOfInterest2D();
174 
175  {
176  auto face = faces["B"].lock();
177  EXPECT_FALSE(face == nullptr);
178 
179  EXPECT_EQ(face->ns(), "/humans/faces/B");
180 
181  EXPECT_FLOAT_EQ(face->roi().xmax, 0.);
182 
183 
184  roi.xmax = 0.3;
185  pub_r2.publish(roi);
186  WAIT;
187  EXPECT_FLOAT_EQ(face->roi().xmax, 0.3);
188 
189  roi.xmax = 0.6;
190  pub_r2.publish(roi);
191  WAIT;
192  EXPECT_FLOAT_EQ(face->roi().xmax, 0.6);
193  }
194 
195  // RoI of face A published *before* face A is published in /faces/tracked,
196  // but should still get its RoI, as /roi is latched.
197  pub_r1.publish(roi);
198  ids.ids = { "B", "A" };
199  pub.publish(ids);
200  WAIT;
201 
202  faces = hri_listener.getFaces();
203  {
204  auto face_a = faces["A"].lock();
205  ASSERT_FALSE(face_a == nullptr);
206  auto face_b = faces["B"].lock();
207  ASSERT_FALSE(face_b == nullptr);
208 
209  EXPECT_EQ(face_a->ns(), "/humans/faces/A");
210  EXPECT_FLOAT_EQ(face_a->roi().xmax, 0.6);
211  EXPECT_EQ(face_b->ns(), "/humans/faces/B");
212  EXPECT_FLOAT_EQ(face_b->roi().xmax, 0.6);
213  }
214 
215  spinner.stop();
216 }
217 
218 TEST(libhri, GetBodies)
219 {
220  NodeHandle nh;
221 
223  spinner.start();
224 
225  Publisher pub;
226 
227  {
228  HRIListener hri_listener;
229 
230  pub = nh.advertise<hri_msgs::IdsList>("/humans/bodies/tracked", 1);
231 
232  ASSERT_EQ(pub.getNumSubscribers(), 1U);
233 
234 
235  auto ids = hri_msgs::IdsList();
236 
237  ROS_INFO("[A]");
238  ids.ids = { "A" };
239  pub.publish(ids);
240  WAIT;
241  auto bodies = hri_listener.getBodies();
242  EXPECT_EQ(bodies.size(), 1U);
243  ASSERT_TRUE(bodies.find("A") != bodies.end());
244  EXPECT_TRUE(bodies["A"].lock()->id() == "A");
245 
246  ROS_INFO("[A]");
247  pub.publish(ids);
248  WAIT;
249  EXPECT_EQ(hri_listener.getBodies().size(), 1U);
250 
251  ROS_INFO("[A,B]");
252  ids.ids = { "A", "B" };
253  pub.publish(ids);
254  WAIT;
255  bodies = hri_listener.getBodies();
256  EXPECT_EQ(bodies.size(), 2U);
257  EXPECT_TRUE(bodies.find("A") != bodies.end());
258  EXPECT_TRUE(bodies.find("B") != bodies.end());
259 
260  ROS_INFO("[A,B]");
261  pub.publish(ids);
262  WAIT;
263  EXPECT_EQ(hri_listener.getBodies().size(), 2U);
264 
265  ROS_INFO("[B]");
266  ids.ids = { "B" };
267  pub.publish(ids);
268  WAIT;
269  bodies = hri_listener.getBodies();
270  EXPECT_EQ(bodies.size(), 1U);
271  EXPECT_TRUE(bodies.find("A") == bodies.end());
272  ASSERT_TRUE(bodies.find("B") != bodies.end());
273 
274  weak_ptr<const Body> body_b = bodies["B"];
275  EXPECT_FALSE(body_b.expired()); // body B exists!
276 
277  ROS_INFO("[]");
278  ids.ids = {};
279  pub.publish(ids);
280  WAIT;
281  EXPECT_EQ(hri_listener.getBodies().size(), 0U);
282 
283  EXPECT_TRUE(body_b.expired()); // body B does not exist anymore!
284  }
285 
286  EXPECT_EQ(pub.getNumSubscribers(), 0);
287  spinner.stop();
288 }
289 
290 TEST(libhri, GetVoices)
291 {
292  NodeHandle nh;
293 
295  spinner.start();
296 
297  Publisher pub;
298 
299  {
300  HRIListener hri_listener;
301 
302  pub = nh.advertise<hri_msgs::IdsList>("/humans/voices/tracked", 1);
303 
304  ASSERT_EQ(pub.getNumSubscribers(), 1U);
305 
306 
307  auto ids = hri_msgs::IdsList();
308 
309  ROS_INFO("[A]");
310  ids.ids = { "A" };
311  pub.publish(ids);
312  WAIT;
313  auto voices = hri_listener.getVoices();
314  EXPECT_EQ(voices.size(), 1U);
315  ASSERT_TRUE(voices.find("A") != voices.end());
316  EXPECT_TRUE(voices["A"].lock()->id() == "A");
317 
318  ROS_INFO("[A]");
319  pub.publish(ids);
320  WAIT;
321  EXPECT_EQ(hri_listener.getVoices().size(), 1U);
322 
323  ROS_INFO("[A,B]");
324  ids.ids = { "A", "B" };
325  pub.publish(ids);
326  WAIT;
327  voices = hri_listener.getVoices();
328  EXPECT_EQ(voices.size(), 2U);
329  EXPECT_TRUE(voices.find("A") != voices.end());
330  EXPECT_TRUE(voices.find("B") != voices.end());
331 
332  ROS_INFO("[A,B]");
333  pub.publish(ids);
334  WAIT;
335  EXPECT_EQ(hri_listener.getVoices().size(), 2U);
336 
337  ROS_INFO("[B]");
338  ids.ids = { "B" };
339  pub.publish(ids);
340  WAIT;
341  voices = hri_listener.getVoices();
342  EXPECT_EQ(voices.size(), 1U);
343  EXPECT_TRUE(voices.find("A") == voices.end());
344  ASSERT_TRUE(voices.find("B") != voices.end());
345 
346  weak_ptr<const Voice> voice_b = voices["B"];
347  EXPECT_FALSE(voice_b.expired()); // voice B exists!
348 
349  ROS_INFO("[]");
350  ids.ids = {};
351  pub.publish(ids);
352  WAIT;
353  EXPECT_EQ(hri_listener.getVoices().size(), 0U);
354 
355  EXPECT_TRUE(voice_b.expired()); // voice B does not exist anymore!
356  }
357 
358  EXPECT_EQ(pub.getNumSubscribers(), 0);
359  spinner.stop();
360 }
361 
362 TEST(libhri, GetKnownPersons)
363 {
364  NodeHandle nh;
365 
367  spinner.start();
368 
369  Publisher pub;
370 
371  {
372  HRIListener hri_listener;
373 
374  pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/known", 1);
375 
376  ASSERT_EQ(pub.getNumSubscribers(), 1U);
377 
378 
379  auto ids = hri_msgs::IdsList();
380 
381  ROS_INFO("[A]");
382  ids.ids = { "A" };
383  pub.publish(ids);
384  WAIT;
385  auto persons = hri_listener.getPersons();
386  EXPECT_EQ(persons.size(), 1U);
387  ASSERT_TRUE(persons.find("A") != persons.end());
388  EXPECT_TRUE(persons["A"].lock()->id() == "A");
389 
390  ROS_INFO("[A]");
391  pub.publish(ids);
392  WAIT;
393  EXPECT_EQ(hri_listener.getPersons().size(), 1U);
394 
395  ROS_INFO("[A,B]");
396  ids.ids = { "A", "B" };
397  pub.publish(ids);
398  WAIT;
399  persons = hri_listener.getPersons();
400  EXPECT_EQ(persons.size(), 2U);
401  EXPECT_TRUE(persons.find("A") != persons.end());
402  EXPECT_TRUE(persons.find("B") != persons.end());
403 
404  ROS_INFO("[A,B]");
405  pub.publish(ids);
406  WAIT;
407  EXPECT_EQ(hri_listener.getPersons().size(), 2U);
408 
409  ROS_INFO("[B]");
410  ids.ids = { "B" };
411  pub.publish(ids);
412  WAIT;
413  persons = hri_listener.getPersons();
414  EXPECT_EQ(persons.size(), 1U) << "known persons can go down in case of eg an anonymous person";
415  EXPECT_TRUE(persons.find("A") == persons.end());
416  ASSERT_TRUE(persons.find("B") != persons.end());
417 
418  shared_ptr<const Person> person_b = persons["B"].lock();
419  EXPECT_TRUE(person_b != nullptr); // person B exists!
420 
421  ROS_INFO("[]");
422  ids.ids = {};
423  pub.publish(ids);
424  WAIT;
425  EXPECT_EQ(hri_listener.getPersons().size(), 0U);
426 
427  EXPECT_TRUE(person_b != nullptr); // person B still exists!
428  }
429 
430  EXPECT_EQ(pub.getNumSubscribers(), 0);
431  spinner.stop();
432 }
433 
434 TEST(libhri, GetTrackedPersons)
435 {
436  NodeHandle nh;
437 
439  spinner.start();
440 
441  Publisher pub;
442 
443  {
444  HRIListener hri_listener;
445 
446  pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
447 
448  ASSERT_EQ(pub.getNumSubscribers(), 1U);
449 
450 
451  auto ids = hri_msgs::IdsList();
452 
453  ROS_INFO("[A]");
454  ids.ids = { "A" };
455  pub.publish(ids);
456  WAIT;
457  auto known_persons = hri_listener.getPersons();
458  EXPECT_EQ(known_persons.size(), 0U);
459 
460  auto persons = hri_listener.getTrackedPersons();
461  EXPECT_EQ(persons.size(), 1U);
462  ASSERT_TRUE(persons.find("A") != persons.end());
463  EXPECT_TRUE(persons["A"].lock()->id() == "A");
464 
465  ROS_INFO("[A]");
466  pub.publish(ids);
467  WAIT;
468  EXPECT_EQ(hri_listener.getTrackedPersons().size(), 1U);
469 
470  ROS_INFO("[A,B]");
471  ids.ids = { "A", "B" };
472  pub.publish(ids);
473  WAIT;
474  persons = hri_listener.getTrackedPersons();
475  EXPECT_EQ(persons.size(), 2U);
476  EXPECT_TRUE(persons.find("A") != persons.end());
477  EXPECT_TRUE(persons.find("B") != persons.end());
478 
479  ROS_INFO("[A,B]");
480  pub.publish(ids);
481  WAIT;
482  EXPECT_EQ(hri_listener.getTrackedPersons().size(), 2U);
483 
484  ROS_INFO("[B]");
485  ids.ids = { "B" };
486  pub.publish(ids);
487  WAIT;
488  persons = hri_listener.getTrackedPersons();
489  EXPECT_EQ(persons.size(), 1U);
490  EXPECT_TRUE(persons.find("A") == persons.end());
491  ASSERT_TRUE(persons.find("B") != persons.end());
492 
493  shared_ptr<const Person> person_b = persons["B"].lock();
494  EXPECT_TRUE(person_b != nullptr); // person B exists!
495 
496  ROS_INFO("[]");
497  ids.ids = {};
498  pub.publish(ids);
499  WAIT;
500  EXPECT_EQ(hri_listener.getTrackedPersons().size(), 0U);
501 
502  EXPECT_TRUE(person_b != nullptr); // person B still exists!
503  }
504 
505  EXPECT_EQ(pub.getNumSubscribers(), 0);
506  spinner.stop();
507 }
508 
509 TEST(libhri, PersonAttributes)
510 {
511  NodeHandle nh;
512 
514  spinner.start();
515 
516  HRIListener hri_listener;
517 
518  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
519  auto face_pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
520  auto person_face_pub = nh.advertise<std_msgs::String>("/humans/persons/p1/face_id", 1);
521 
522  auto person_ids = hri_msgs::IdsList();
523  person_ids.ids = { "p1" };
524  person_pub.publish(person_ids);
525 
526  auto face_ids = hri_msgs::IdsList();
527  face_ids.ids = { "f1", "f2" };
528  face_pub.publish(face_ids);
529 
530  WAIT;
531 
532  auto p1 = hri_listener.getTrackedPersons()["p1"].lock();
533 
534  ASSERT_FALSE(p1->anonymous()) << "whether a person is anonymous or not has to be explicitely set";
535 
536  auto face0 = p1->face();
537 
538  ASSERT_EQ(face0.lock(), nullptr);
539  ASSERT_TRUE(face0.expired());
540 
541  auto face_id = std_msgs::String();
542  face_id.data = "f1";
543 
544  person_face_pub.publish(face_id);
545 
546  WAIT;
547 
548  auto face1 = hri_listener.getTrackedPersons()["p1"].lock()->face();
549 
550  ASSERT_NE(face1.lock(), nullptr);
551  ASSERT_FALSE(face1.expired());
552  ASSERT_EQ(face1.lock()->id(), "f1");
553 
554  spinner.stop();
555 }
556 
557 TEST(libhri, AnonymousPersonsAndAliases)
558 {
559  NodeHandle nh;
560 
562  spinner.start();
563 
564  HRIListener hri_listener;
565 
566  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
567  auto p1_anon_pub = nh.advertise<std_msgs::Bool>("/humans/persons/p1/anonymous", 1);
568  auto p2_anon_pub = nh.advertise<std_msgs::Bool>("/humans/persons/p2/anonymous", 1);
569 
570  auto face_pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
571  auto p1_face_pub = nh.advertise<std_msgs::String>("/humans/persons/p1/face_id", 1);
572  auto p2_face_pub = nh.advertise<std_msgs::String>("/humans/persons/p2/face_id", 1);
573 
574  auto p2_alias_pub = nh.advertise<std_msgs::String>("/humans/persons/p2/alias", 1);
575 
576  auto person_ids = hri_msgs::IdsList();
577  person_ids.ids = { "p1", "p2" };
578  person_pub.publish(person_ids);
579 
580  auto face_ids = hri_msgs::IdsList();
581  face_ids.ids = { "f1", "f2" };
582  face_pub.publish(face_ids);
583 
584  WAIT;
585 
586  // each person is associated to a face
587  auto face_id = std_msgs::String();
588  face_id.data = "f1";
589  p1_face_pub.publish(face_id);
590  face_id.data = "f2";
591  p2_face_pub.publish(face_id);
592 
593 
594  WAIT;
595 
596  std_msgs::Bool msg;
597  msg.data = false;
598  p1_anon_pub.publish(msg);
599  msg.data = true;
600  p2_anon_pub.publish(msg);
601 
602  WAIT;
603 
604  ASSERT_EQ(hri_listener.getTrackedPersons().size(), 2);
605 
606  auto p1 = hri_listener.getTrackedPersons()["p1"].lock();
607 
608  {
609  auto p2 = hri_listener.getTrackedPersons()["p2"].lock();
610 
611  ASSERT_TRUE(p1->anonymous()); // the anonymous optional flag should have been set
612  ASSERT_TRUE(p2->anonymous()); // the anonymous optional flag should have been set
613  ASSERT_FALSE(*(p1->anonymous()));
614  ASSERT_TRUE(*(p2->anonymous()));
615 
616  // being anonymous or not should have no impact on face associations
617  ASSERT_EQ(p1->face().lock()->id(), "f1");
618  ASSERT_EQ(p2->face().lock()->id(), "f2");
619  }
620 
622 
623  // set p2 as an alias of p1
624  auto alias_id = std_msgs::String();
625  alias_id.data = "p1";
626 
627  p2_alias_pub.publish(alias_id);
628 
629  WAIT;
630 
631  ASSERT_EQ(hri_listener.getTrackedPersons().size(), 2U);
632 
633  {
634  auto p2 = hri_listener.getTrackedPersons()["p2"].lock();
635 
636  ASSERT_EQ(p1, p2) << "p2 should now point to the same person as p1";
637 
638  ASSERT_EQ(p2->face().lock()->id(), "f1") << "p2's face now points to f1";
639  }
640  // remove the alias
641  alias_id.data = "";
642 
643  p2_alias_pub.publish(alias_id);
644 
645  WAIT;
646 
647  {
648  auto p2 = hri_listener.getTrackedPersons()["p2"].lock();
649 
650  ASSERT_NE(p1, p2) << "p2 is not anymore the same person as p1";
651 
652  ASSERT_EQ(p2->face().lock()->id(), "f2")
653  << "p2's face should still points to its former f2 face";
654  }
655 
656  // republish the alias
657  alias_id.data = "p1";
658 
659  p2_alias_pub.publish(alias_id);
660 
661  WAIT;
662 
663  auto p2 = hri_listener.getTrackedPersons()["p2"].lock();
664 
665  ASSERT_EQ(p1, p2) << "p2 is again the same person as p1";
666 
667  // delete p1 -> p2 should be deleted as well
668 
669  person_ids.ids = { "p2" };
670  person_pub.publish(person_ids);
671 
672  WAIT;
673 
674  ASSERT_EQ(hri_listener.getTrackedPersons().size(), 0U)
675  << "the aliased person should have been deleted with its alias";
676 
677  spinner.stop();
678 }
679 
680 
681 TEST(libhri, Callbacks)
682 {
683  NodeHandle nh;
684 
686  spinner.start();
687 
688  HRIListener hri_listener;
689 
690  // create mock callbacks
691  testing::MockFunction<void(FaceWeakConstPtr)> face_callback;
692  hri_listener.onFace(face_callback.AsStdFunction());
693 
694  testing::MockFunction<void(ID)> face_lost_callback;
695  hri_listener.onFaceLost(face_lost_callback.AsStdFunction());
696 
697 
698  testing::MockFunction<void(BodyWeakConstPtr)> body_callback;
699  hri_listener.onBody(body_callback.AsStdFunction());
700 
701  testing::MockFunction<void(ID)> body_lost_callback;
702  hri_listener.onBodyLost(body_lost_callback.AsStdFunction());
703 
704 
705  testing::MockFunction<void(VoiceWeakConstPtr)> voice_callback;
706  hri_listener.onVoice(voice_callback.AsStdFunction());
707 
708  testing::MockFunction<void(ID)> voice_lost_callback;
709  hri_listener.onVoiceLost(voice_lost_callback.AsStdFunction());
710 
711 
712  testing::MockFunction<void(PersonWeakConstPtr)> person_callback;
713  hri_listener.onPerson(person_callback.AsStdFunction());
714 
715  testing::MockFunction<void(PersonWeakConstPtr)> person_tracked_callback;
716  hri_listener.onTrackedPerson(person_tracked_callback.AsStdFunction());
717 
718  testing::MockFunction<void(ID)> person_tracked_lost_callback;
719  hri_listener.onTrackedPersonLost(person_tracked_lost_callback.AsStdFunction());
720 
721 
722 
723  auto ids = hri_msgs::IdsList();
724 
725  auto face_pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
726  auto body_pub = nh.advertise<hri_msgs::IdsList>("/humans/bodies/tracked", 1);
727  auto voice_pub = nh.advertise<hri_msgs::IdsList>("/humans/voices/tracked", 1);
728  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/known", 1);
729  auto person_tracked_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
730 
731 
732  // uses a workaround to fake interleaving of EXPECT_CALL with function calls, see https://stackoverflow.com/a/60905880
733  uint32_t face_call_count = 0;
734  EXPECT_CALL(face_callback, Call(testing::_)).WillRepeatedly(
735  testing::InvokeWithoutArgs([&face_call_count](){ face_call_count++; }));
736 
737  uint32_t face_lost_call_count = 0;
738  EXPECT_CALL(face_lost_callback, Call(testing::_)).WillRepeatedly(
739  testing::InvokeWithoutArgs([&face_lost_call_count](){ face_lost_call_count++; }));
740 
741  uint32_t body_call_count = 0;
742  EXPECT_CALL(body_callback, Call(testing::_)).WillRepeatedly(
743  testing::InvokeWithoutArgs([&body_call_count](){ body_call_count++; }));
744 
745  uint32_t body_lost_call_count = 0;
746  EXPECT_CALL(body_lost_callback, Call(testing::_)).WillRepeatedly(
747  testing::InvokeWithoutArgs([&body_lost_call_count](){ body_lost_call_count++; }));
748 
749  uint32_t voice_call_count = 0;
750  EXPECT_CALL(voice_callback, Call(testing::_)).WillRepeatedly(
751  testing::InvokeWithoutArgs([&voice_call_count](){ voice_call_count++; }));
752 
753  uint32_t voice_lost_call_count = 0;
754  EXPECT_CALL(voice_lost_callback, Call(testing::_)).WillRepeatedly(
755  testing::InvokeWithoutArgs([&voice_lost_call_count](){ voice_lost_call_count++; }));
756 
757  uint32_t person_call_count = 0;
758  EXPECT_CALL(person_callback, Call(testing::_)).WillRepeatedly(
759  testing::InvokeWithoutArgs([&person_call_count](){ person_call_count++; }));
760 
761  uint32_t person_tracked_call_count = 0;
762  EXPECT_CALL(person_tracked_callback, Call(testing::_)).WillRepeatedly(
763  testing::InvokeWithoutArgs([&person_tracked_call_count](){ person_tracked_call_count++; }));
764 
765  uint32_t person_tracked_lost_call_count = 0;
766  EXPECT_CALL(person_tracked_lost_callback, Call(testing::_)).WillRepeatedly(
767  testing::InvokeWithoutArgs([&person_tracked_lost_call_count](){ person_tracked_lost_call_count++; }));
768 
769 
770  // start sequential testing
771  face_call_count = 0;
772  face_lost_call_count = 0;
773  ids.ids = { "id1" };
774  face_pub.publish(ids);
775  WAIT_LONG;
776  EXPECT_EQ(face_call_count, 1);
777  EXPECT_EQ(face_lost_call_count, 0);
778 
779 
780  face_call_count = 0;
781  face_lost_call_count = 0;
782  ids.ids = { "id1", "id2" };
783  face_pub.publish(ids);
784  WAIT_LONG;
785  EXPECT_EQ(face_call_count, 1);
786  EXPECT_EQ(face_lost_call_count, 0);
787 
788  face_call_count = 0;
789  face_lost_call_count = 0;
790  ids.ids = { "id3", "id4" };
791  face_pub.publish(ids);
792  WAIT_LONG;
793  EXPECT_EQ(face_call_count, 2);
794  EXPECT_EQ(face_lost_call_count, 2);
795 
796  body_call_count = 0;
797  body_lost_call_count = 0;
798  ids.ids = { "id1", "id2" };
799  body_pub.publish(ids);
800  WAIT_LONG;
801  EXPECT_EQ(body_call_count, 2);
802  EXPECT_EQ(body_lost_call_count, 0);
803 
804  face_call_count = 0;
805  face_lost_call_count = 0;
806  body_call_count = 0;
807  body_lost_call_count = 0;
808  ids.ids = { "id1", "id2", "id3" };
809  face_pub.publish(ids);
810  body_pub.publish(ids);
811  WAIT_LONG;
812  EXPECT_EQ(face_call_count, 2);
813  EXPECT_EQ(face_lost_call_count, 1);
814  EXPECT_EQ(body_call_count, 1);
815  EXPECT_EQ(body_lost_call_count, 0);
816 
817  face_call_count = 0;
818  face_lost_call_count = 0;
819  body_call_count = 0;
820  body_lost_call_count = 0;
821  ids.ids = { "id5", "id6", "id7" };
822  face_pub.publish(ids);
823  body_pub.publish(ids);
824  WAIT_LONG;
825  EXPECT_EQ(face_call_count, 3);
826  EXPECT_EQ(face_lost_call_count, 3);
827  EXPECT_EQ(body_call_count, 3);
828  EXPECT_EQ(body_lost_call_count, 3);
829 
830  voice_call_count = 0;
831  person_call_count = 0;
832  person_tracked_call_count = 0;
833  ids.ids = { "id1", "id2" };
834  voice_pub.publish(ids);
835  person_pub.publish(ids);
836  person_tracked_pub.publish(ids);
837  WAIT_LONG;
838  EXPECT_EQ(voice_call_count, 2);
839  EXPECT_EQ(person_call_count, 2);
840  EXPECT_EQ(person_tracked_call_count, 2);
841 
842  spinner.stop();
843 }
844 
845 TEST(libhri, SoftBiometrics)
846 {
847  NodeHandle nh;
848 
850  spinner.start();
851 
852  HRIListener hri_listener;
853 
854  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
855  auto face_pub = nh.advertise<hri_msgs::IdsList>("/humans/faces/tracked", 1);
856  auto person_face_pub = nh.advertise<std_msgs::String>("/humans/persons/p1/face_id", 1);
857  auto softbiometrics_pub =
858  nh.advertise<hri_msgs::SoftBiometrics>("/humans/faces/f1/softbiometrics", 1);
859 
860  auto person_ids = hri_msgs::IdsList();
861  person_ids.ids = { "p1" };
862  person_pub.publish(person_ids);
863 
864  auto face_ids = hri_msgs::IdsList();
865  face_ids.ids = { "f1" };
866  face_pub.publish(face_ids);
867 
868  WAIT;
869 
870  auto softbiometrics_msg = hri_msgs::SoftBiometrics();
871  softbiometrics_msg.age = 45;
872  softbiometrics_msg.age_confidence = 0.8;
873  softbiometrics_msg.gender = hri_msgs::SoftBiometrics::FEMALE;
874  softbiometrics_msg.gender_confidence = 0.7;
875  softbiometrics_pub.publish(softbiometrics_msg);
876 
877  auto face_id = std_msgs::String();
878  face_id.data = "f1";
879 
880  person_face_pub.publish(face_id);
881 
882  WAIT;
883 
884  auto face = hri_listener.getTrackedPersons()["p1"].lock()->face().lock();
885 
886  ASSERT_EQ(face->id(), "f1");
887 
888  ASSERT_TRUE(face->age());
889  ASSERT_EQ(*(face->age()), 45);
890  ASSERT_TRUE(face->gender());
891  ASSERT_EQ(*(face->gender()), hri::FEMALE);
892 
893  softbiometrics_msg.gender = hri_msgs::SoftBiometrics::OTHER;
894  softbiometrics_pub.publish(softbiometrics_msg);
895  WAIT;
896 
897  ASSERT_EQ(*(face->gender()), hri::OTHER);
898 
899  softbiometrics_msg.gender = hri_msgs::SoftBiometrics::UNDEFINED;
900  softbiometrics_pub.publish(softbiometrics_msg);
901  WAIT;
902 
903  ASSERT_FALSE(face->gender());
904 
905  spinner.stop();
906 }
907 
909 {
910  NodeHandle nh;
911 
913  spinner.start();
914 
915  HRIListener hri_listener;
916 
917  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
918  auto engagement_pub =
919  nh.advertise<hri_msgs::EngagementLevel>("/humans/persons/p1/engagement_status", 1);
920 
921  auto person_ids = hri_msgs::IdsList();
922  person_ids.ids = { "p1" };
923  person_pub.publish(person_ids);
924 
925  WAIT;
926 
927  auto msg = hri_msgs::EngagementLevel();
929  engagement_pub.publish(msg);
930 
931  WAIT;
932 
933  auto p = hri_listener.getTrackedPersons()["p1"].lock();
934  ASSERT_TRUE(p->engagement_status());
935  ASSERT_EQ(*(p->engagement_status()), hri::DISENGAGED);
936 
938  engagement_pub.publish(msg);
939  WAIT;
940 
941  ASSERT_EQ(*(p->engagement_status()), hri::ENGAGED);
942 
943  msg.level = hri_msgs::EngagementLevel::UNKNOWN;
944  engagement_pub.publish(msg);
945  WAIT;
946 
947  ASSERT_FALSE(p->engagement_status());
948 
949  spinner.stop();
950 }
951 
952 TEST(libhri, PeopleLocation)
953 {
954  NodeHandle nh;
955 
957  spinner.start();
958 
959  HRIListener hri_listener;
960  hri_listener.setReferenceFrame("base_link");
961 
962  tf2_ros::StaticTransformBroadcaster static_broadcaster;
963 
964  geometry_msgs::TransformStamped world_transform;
965  world_transform.header.stamp = ros::Time::now();
966  world_transform.header.frame_id = "world";
967  world_transform.child_frame_id = "base_link";
968  world_transform.transform.translation.x = -1.0;
969  world_transform.transform.translation.y = 0.0;
970  world_transform.transform.translation.z = 0.0;
971  world_transform.transform.rotation.w = 1.0;
972  static_broadcaster.sendTransform(world_transform);
973 
974  geometry_msgs::TransformStamped p1_transform;
975  p1_transform.header.stamp = ros::Time::now();
976  p1_transform.header.frame_id = "world";
977  p1_transform.child_frame_id = "person_p1";
978  p1_transform.transform.translation.x = 1.0;
979  p1_transform.transform.translation.y = 0.0;
980  p1_transform.transform.translation.z = 0.0;
981  p1_transform.transform.rotation.w = 1.0;
982 
983  auto person_pub = nh.advertise<hri_msgs::IdsList>("/humans/persons/tracked", 1);
984  auto loc_confidence_pub =
985  nh.advertise<std_msgs::Float32>("/humans/persons/p1/location_confidence", 1);
986 
987  auto person_ids = hri_msgs::IdsList();
988  person_ids.ids = { "p1" };
989  person_pub.publish(person_ids);
990 
991  WAIT;
992 
993  auto p = hri_listener.getTrackedPersons()["p1"].lock();
994 
995  auto msg = std_msgs::Float32();
996  msg.data = 0.;
997  loc_confidence_pub.publish(msg);
998  WAIT;
999 
1000  ASSERT_EQ(p->location_confidence(), 0.);
1001  ASSERT_FALSE(p->transform()) << "location confidence at 0, no transform should be available";
1002 
1003  msg.data = 0.5;
1004  loc_confidence_pub.publish(msg);
1005  WAIT;
1006 
1007  ASSERT_EQ(p->location_confidence(), 0.5);
1008  p->transform();
1009  ASSERT_FALSE(p->transform()) << "location confidence > 0 but no transform published yet -> no transform should be returned";
1010 
1011 
1012  static_broadcaster.sendTransform(p1_transform);
1013  WAIT;
1014 
1015  ASSERT_EQ(p->location_confidence(), 0.5);
1016  ASSERT_TRUE(p->transform()) << "location confidence > 0 => a transform should be available";
1017  auto t = *(p->transform());
1018  ASSERT_EQ(t.child_frame_id, "person_p1");
1019  ASSERT_EQ(t.header.frame_id, "base_link");
1020  ASSERT_EQ(t.transform.translation.x, 2.0);
1021 
1022 
1023  msg.data = 1.0;
1024  loc_confidence_pub.publish(msg);
1025  WAIT;
1026 
1027  ASSERT_EQ(p->location_confidence(), 1.);
1028  ASSERT_TRUE(p->transform()) << "location confidence > 0 => a transform should be available";
1029 
1030  spinner.stop();
1031 }
1032 
1033 TEST(libhri, SpeechCallbacks)
1034 {
1035  NodeHandle nh;
1036 
1038  spinner.start();
1039 
1040  HRIListener hri_listener;
1041 
1042  // create mock callbacks
1043  testing::MockFunction<void(bool)> is_speaking_callback;
1044  testing::MockFunction<void(string)> speech_callback;
1045  testing::MockFunction<void(string)> incremental_speech_callback;
1046 
1047  hri_listener.onVoice([&](VoiceWeakPtr weak_voice) {
1048  auto voice = weak_voice.lock();
1049  voice->onSpeaking(is_speaking_callback.AsStdFunction());
1050  voice->onSpeech(speech_callback.AsStdFunction());
1051  voice->onIncrementalSpeech(incremental_speech_callback.AsStdFunction());
1052  });
1053 
1054  // testing::MockFunction<void(ID)> voice_lost_callback;
1055  // hri_listener.onVoiceLost(voice_lost_callback.AsStdFunction());
1056 
1057  auto ids = hri_msgs::IdsList();
1058  auto is_speaking = std_msgs::Bool();
1059  auto speech = hri_msgs::LiveSpeech();
1060 
1061  auto voice_pub = nh.advertise<hri_msgs::IdsList>("/humans/voices/tracked", 1);
1062  auto is_speaking_pub = nh.advertise<std_msgs::Bool>("/humans/voices/id1/is_speaking", 1);
1063  auto speech_pub = nh.advertise<hri_msgs::LiveSpeech>("/humans/voices/id1/speech", 1);
1064 
1065 
1066  // uses a workaround to fake interleaving of EXPECT_CALL with function calls, see https://stackoverflow.com/a/60905880
1067  uint32_t is_speaking_call_count = 0;
1068  EXPECT_CALL(is_speaking_callback, Call(testing::_)).WillRepeatedly(
1069  testing::InvokeWithoutArgs([&is_speaking_call_count](){ is_speaking_call_count++; }));
1070 
1071  uint32_t speech_call_count = 0;
1072  EXPECT_CALL(speech_callback, Call(testing::_)).WillRepeatedly(
1073  testing::InvokeWithoutArgs([&speech_call_count](){ speech_call_count++; }));
1074 
1075  uint32_t incremental_speech_call_count = 0;
1076  EXPECT_CALL(incremental_speech_callback, Call(testing::_)).WillRepeatedly(
1077  testing::InvokeWithoutArgs([&incremental_speech_call_count](){ incremental_speech_call_count++; }));
1078 
1079 
1080  // start sequential testing
1081  ids.ids = { "id1" };
1082  voice_pub.publish(ids);
1083  WAIT;
1084 
1085  is_speaking_call_count = 0;
1086  speech_call_count = 0;
1087  incremental_speech_call_count = 0;
1088  is_speaking.data = true;
1089  is_speaking_pub.publish(is_speaking);
1090  WAIT;
1091  EXPECT_EQ(is_speaking_call_count, 1);
1092  EXPECT_EQ(speech_call_count, 0);
1093  EXPECT_EQ(incremental_speech_call_count, 0);
1094 
1095  is_speaking_call_count = 0;
1096  is_speaking.data = false;
1097  is_speaking_pub.publish(is_speaking);
1098  WAIT;
1099  EXPECT_EQ(is_speaking_call_count, 1);
1100 
1101  is_speaking_call_count = 0;
1102  speech_call_count = 0;
1103  incremental_speech_call_count = 0;
1104  speech.final = "final sentence";
1105  speech.incremental = "";
1106  speech_pub.publish(speech);
1107  WAIT;
1108  EXPECT_EQ(is_speaking_call_count, 0);
1109  EXPECT_EQ(speech_call_count, 1);
1110  EXPECT_EQ(incremental_speech_call_count, 0);
1111 
1112  is_speaking_call_count = 0;
1113  speech_call_count = 0;
1114  incremental_speech_call_count = 0;
1115  speech.final = "";
1116  speech.incremental = "incremental sentence";
1117  speech_pub.publish(speech);
1118  WAIT;
1119  EXPECT_EQ(is_speaking_call_count, 0);
1120  EXPECT_EQ(speech_call_count, 0);
1121  EXPECT_EQ(incremental_speech_call_count, 1);
1122 
1123  is_speaking_call_count = 0;
1124  speech_call_count = 0;
1125  incremental_speech_call_count = 0;
1126  speech.final = "final sentence";
1127  speech.incremental = "incremental sentence";
1128  speech_pub.publish(speech);
1129  WAIT;
1130  EXPECT_EQ(is_speaking_call_count, 0);
1131  EXPECT_EQ(speech_call_count, 1);
1132  EXPECT_EQ(incremental_speech_call_count, 1);
1133 
1134  spinner.stop();
1135 }
1136 
1137 int main(int argc, char** argv)
1138 {
1139  testing::InitGoogleTest(&argc, argv);
1140  ros::Time::init(); // needed for ros::Time::now()
1141  ros::init(argc, argv, "test_hri");
1142  ros::NodeHandle nh;
1143  ROS_INFO("Starting HRI tests");
1144  return RUN_ALL_TESTS();
1145 }
1146 
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
hri
Definition: base.h:38
face.h
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros
ros.h
WAIT_LONG
#define WAIT_LONG
Definition: test_hri.cpp:56
hri::FEMALE
@ FEMALE
Definition: face.h:60
ros::AsyncSpinner
hri::VoiceWeakPtr
std::weak_ptr< Voice > VoiceWeakPtr
Definition: voice.h:148
hri::HRIListener::onFaceLost
void onFaceLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked face is lost (eg,...
Definition: hri.h:94
hri::DISENGAGED
@ DISENGAGED
Definition: person.h:58
hri::HRIListener::getBodies
std::map< ID, BodyWeakConstPtr > getBodies() const
Returns the list of currently detected bodies, mapped to their IDs.
Definition: hri.cpp:76
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
hri::HRIListener::getPersons
std::map< ID, PersonWeakConstPtr > getPersons() const
Returns the list of all known persons, whether or not they are currently actively detected (eg,...
Definition: hri.cpp:104
hri::OTHER
@ OTHER
Definition: face.h:62
hri::HRIListener::onTrackedPerson
void onTrackedPerson(std::function< void(PersonWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new person is detected and actively tracked ...
Definition: hri.h:187
hri::HRIListener::getTrackedPersons
std::map< ID, PersonWeakConstPtr > getTrackedPersons() const
Returns the list of currently detected persons, mapped to their IDs.
Definition: hri.cpp:139
spinner
void spinner()
hri::ENGAGED
@ ENGAGED
Definition: person.h:62
tf2_ros::StaticTransformBroadcaster
hri::VoiceWeakConstPtr
std::weak_ptr< const Voice > VoiceWeakConstPtr
Definition: voice.h:149
TEST
TEST(libhri, GetFaces)
Definition: test_hri.cpp:63
hri::FaceWeakConstPtr
std::weak_ptr< const Face > FaceWeakConstPtr
Definition: face.h:211
hri::HRIListener::onVoiceLost
void onVoiceLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked voice is lost (eg,...
Definition: hri.h:140
main
int main(int argc, char **argv)
Definition: test_hri.cpp:1137
hri::HRIListener::onBody
void onBody(std::function< void(BodyWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new body is detected.
Definition: hri.h:109
hri.h
hri::HRIListener::onFace
void onFace(std::function< void(FaceWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new face is detected.
Definition: hri.h:86
hri::BodyWeakConstPtr
std::weak_ptr< const Body > BodyWeakConstPtr
Definition: body.h:139
hri::EngagementLevel
EngagementLevel
Definition: person.h:55
ros::NodeHandle
WAIT
#define WAIT
Definition: test_hri.cpp:55
hri::HRIListener::onBodyLost
void onBodyLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked body is lost (eg,...
Definition: hri.h:117
ros::Publisher
hri::HRIListener::onPerson
void onPerson(std::function< void(PersonWeakConstPtr)> callback)
Registers a callback function, to be invoked everytime a new person is detected.
Definition: hri.h:161
hri::PersonWeakConstPtr
std::weak_ptr< const Person > PersonWeakConstPtr
Definition: person.h:164
hri::HRIListener::getFaces
std::map< ID, FaceWeakConstPtr > getFaces() const
Returns the list of currently detected faces, mapped to their IDs.
Definition: hri.cpp:62
ros::Time::init
static void init()
hri::face
@ face
Definition: base.h:47
hri::HRIListener
Main entry point to libhri. This is most likely what you want to use. Use example:
Definition: hri.h:70
std
hri::HRIListener::onTrackedPersonLost
void onTrackedPersonLost(std::function< void(ID)> callback)
Registers a callback function, to be invoked everytime a previously tracked person is lost.
Definition: hri.h:195
hri::voice
@ voice
Definition: base.h:49
static_transform_broadcaster.h
hri::ID
std::string ID
Definition: base.h:40
hri::HRIListener::getVoices
std::map< ID, VoiceWeakConstPtr > getVoices() const
Returns the list of currently detected voices, mapped to their IDs.
Definition: hri.cpp:90
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
voice.h
hri::HRIListener::onVoice
void onVoice(std::function< void(VoiceWeakPtr)> callback)
Registers a callback function, to be invoked everytime a new voice is detected.
Definition: hri.h:132
ROS_INFO
#define ROS_INFO(...)
person.h
hri::HRIListener::setReferenceFrame
void setReferenceFrame(const std::string &frame)
Definition: hri.h:206
ros::NodeHandle
ros::Time::now
static Time now()


libhri
Author(s): Séverin Lemaignan
autogenerated on Thu Jul 6 2023 02:43:58