29 #include <gtest/gtest.h>
30 #include <gmock/gmock.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>
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))
60 cout << "waiting..." << endl; \
75 pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/faces/tracked", 1);
79 ASSERT_EQ(hri_listener.
getFaces().size(), 0);
81 auto ids = hri_msgs::IdsList();
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");
95 EXPECT_EQ(hri_listener.
getFaces().size(), 1U);
98 ids.ids = {
"A",
"B" };
102 EXPECT_EQ(faces.size(), 2U);
103 EXPECT_TRUE(faces.find(
"A") != faces.end());
104 EXPECT_TRUE(faces.find(
"B") != faces.end());
109 EXPECT_EQ(hri_listener.
getFaces().size(), 2U);
116 EXPECT_EQ(faces.size(), 1U);
117 EXPECT_TRUE(faces.find(
"A") == faces.end());
118 ASSERT_TRUE(faces.find(
"B") != faces.end());
120 weak_ptr<const Face> face_b = faces[
"B"];
121 EXPECT_FALSE(face_b.expired());
127 EXPECT_EQ(hri_listener.
getFaces().size(), 0U);
129 EXPECT_TRUE(face_b.expired());
145 auto pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/faces/tracked", 1);
147 auto pub_r1 = nh.
advertise<hri_msgs::NormalizedRegionOfInterest2D>(
"/humans/faces/A/roi", 1,
true);
148 auto pub_r2 = nh.
advertise<hri_msgs::NormalizedRegionOfInterest2D>(
"/humans/faces/B/roi", 1,
true);
150 auto ids = hri_msgs::IdsList();
156 EXPECT_EQ(pub_r1.getNumSubscribers(), 1U)
157 <<
"Face A should have subscribed to /humans/faces/A/roi";
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";
170 auto faces = hri_listener.
getFaces();
171 ASSERT_FALSE(faces[
"B"].expired());
173 auto roi = hri_msgs::NormalizedRegionOfInterest2D();
176 auto face = faces[
"B"].lock();
177 EXPECT_FALSE(
face ==
nullptr);
179 EXPECT_EQ(
face->ns(),
"/humans/faces/B");
181 EXPECT_FLOAT_EQ(
face->roi().xmax, 0.);
187 EXPECT_FLOAT_EQ(
face->roi().xmax, 0.3);
192 EXPECT_FLOAT_EQ(
face->roi().xmax, 0.6);
198 ids.ids = {
"B",
"A" };
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);
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);
230 pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/bodies/tracked", 1);
235 auto ids = hri_msgs::IdsList();
242 EXPECT_EQ(bodies.size(), 1U);
243 ASSERT_TRUE(bodies.find(
"A") != bodies.end());
244 EXPECT_TRUE(bodies[
"A"].lock()->
id() ==
"A");
249 EXPECT_EQ(hri_listener.
getBodies().size(), 1U);
252 ids.ids = {
"A",
"B" };
256 EXPECT_EQ(bodies.size(), 2U);
257 EXPECT_TRUE(bodies.find(
"A") != bodies.end());
258 EXPECT_TRUE(bodies.find(
"B") != bodies.end());
263 EXPECT_EQ(hri_listener.
getBodies().size(), 2U);
270 EXPECT_EQ(bodies.size(), 1U);
271 EXPECT_TRUE(bodies.find(
"A") == bodies.end());
272 ASSERT_TRUE(bodies.find(
"B") != bodies.end());
274 weak_ptr<const Body> body_b = bodies[
"B"];
275 EXPECT_FALSE(body_b.expired());
281 EXPECT_EQ(hri_listener.
getBodies().size(), 0U);
283 EXPECT_TRUE(body_b.expired());
302 pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/voices/tracked", 1);
307 auto ids = hri_msgs::IdsList();
314 EXPECT_EQ(voices.size(), 1U);
315 ASSERT_TRUE(voices.find(
"A") != voices.end());
316 EXPECT_TRUE(voices[
"A"].lock()->
id() ==
"A");
321 EXPECT_EQ(hri_listener.
getVoices().size(), 1U);
324 ids.ids = {
"A",
"B" };
328 EXPECT_EQ(voices.size(), 2U);
329 EXPECT_TRUE(voices.find(
"A") != voices.end());
330 EXPECT_TRUE(voices.find(
"B") != voices.end());
335 EXPECT_EQ(hri_listener.
getVoices().size(), 2U);
342 EXPECT_EQ(voices.size(), 1U);
343 EXPECT_TRUE(voices.find(
"A") == voices.end());
344 ASSERT_TRUE(voices.find(
"B") != voices.end());
346 weak_ptr<const Voice> voice_b = voices[
"B"];
347 EXPECT_FALSE(voice_b.expired());
353 EXPECT_EQ(hri_listener.
getVoices().size(), 0U);
355 EXPECT_TRUE(voice_b.expired());
374 pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/persons/known", 1);
379 auto ids = hri_msgs::IdsList();
386 EXPECT_EQ(persons.size(), 1U);
387 ASSERT_TRUE(persons.find(
"A") != persons.end());
388 EXPECT_TRUE(persons[
"A"].lock()->
id() ==
"A");
393 EXPECT_EQ(hri_listener.
getPersons().size(), 1U);
396 ids.ids = {
"A",
"B" };
400 EXPECT_EQ(persons.size(), 2U);
401 EXPECT_TRUE(persons.find(
"A") != persons.end());
402 EXPECT_TRUE(persons.find(
"B") != persons.end());
407 EXPECT_EQ(hri_listener.
getPersons().size(), 2U);
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());
418 shared_ptr<const Person> person_b = persons[
"B"].lock();
419 EXPECT_TRUE(person_b !=
nullptr);
425 EXPECT_EQ(hri_listener.
getPersons().size(), 0U);
427 EXPECT_TRUE(person_b !=
nullptr);
434 TEST(libhri, GetTrackedPersons)
446 pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/persons/tracked", 1);
451 auto ids = hri_msgs::IdsList();
457 auto known_persons = hri_listener.
getPersons();
458 EXPECT_EQ(known_persons.size(), 0U);
461 EXPECT_EQ(persons.size(), 1U);
462 ASSERT_TRUE(persons.find(
"A") != persons.end());
463 EXPECT_TRUE(persons[
"A"].lock()->
id() ==
"A");
471 ids.ids = {
"A",
"B" };
475 EXPECT_EQ(persons.size(), 2U);
476 EXPECT_TRUE(persons.find(
"A") != persons.end());
477 EXPECT_TRUE(persons.find(
"B") != persons.end());
489 EXPECT_EQ(persons.size(), 1U);
490 EXPECT_TRUE(persons.find(
"A") == persons.end());
491 ASSERT_TRUE(persons.find(
"B") != persons.end());
493 shared_ptr<const Person> person_b = persons[
"B"].lock();
494 EXPECT_TRUE(person_b !=
nullptr);
502 EXPECT_TRUE(person_b !=
nullptr);
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);
522 auto person_ids = hri_msgs::IdsList();
523 person_ids.ids = {
"p1" };
524 person_pub.publish(person_ids);
526 auto face_ids = hri_msgs::IdsList();
527 face_ids.ids = {
"f1",
"f2" };
528 face_pub.publish(face_ids);
534 ASSERT_FALSE(p1->anonymous()) <<
"whether a person is anonymous or not has to be explicitely set";
536 auto face0 = p1->face();
538 ASSERT_EQ(face0.lock(),
nullptr);
539 ASSERT_TRUE(face0.expired());
541 auto face_id = std_msgs::String();
544 person_face_pub.publish(face_id);
550 ASSERT_NE(face1.lock(),
nullptr);
551 ASSERT_FALSE(face1.expired());
552 ASSERT_EQ(face1.lock()->id(),
"f1");
557 TEST(libhri, AnonymousPersonsAndAliases)
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);
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);
574 auto p2_alias_pub = nh.
advertise<std_msgs::String>(
"/humans/persons/p2/alias", 1);
576 auto person_ids = hri_msgs::IdsList();
577 person_ids.ids = {
"p1",
"p2" };
578 person_pub.publish(person_ids);
580 auto face_ids = hri_msgs::IdsList();
581 face_ids.ids = {
"f1",
"f2" };
582 face_pub.publish(face_ids);
587 auto face_id = std_msgs::String();
589 p1_face_pub.publish(face_id);
591 p2_face_pub.publish(face_id);
598 p1_anon_pub.publish(msg);
600 p2_anon_pub.publish(msg);
611 ASSERT_TRUE(p1->anonymous());
612 ASSERT_TRUE(p2->anonymous());
613 ASSERT_FALSE(*(p1->anonymous()));
614 ASSERT_TRUE(*(p2->anonymous()));
617 ASSERT_EQ(p1->face().lock()->id(),
"f1");
618 ASSERT_EQ(p2->face().lock()->id(),
"f2");
624 auto alias_id = std_msgs::String();
625 alias_id.data =
"p1";
627 p2_alias_pub.publish(alias_id);
636 ASSERT_EQ(p1, p2) <<
"p2 should now point to the same person as p1";
638 ASSERT_EQ(p2->face().lock()->id(),
"f1") <<
"p2's face now points to f1";
643 p2_alias_pub.publish(alias_id);
650 ASSERT_NE(p1, p2) <<
"p2 is not anymore the same person as p1";
652 ASSERT_EQ(p2->face().lock()->id(),
"f2")
653 <<
"p2's face should still points to its former f2 face";
657 alias_id.data =
"p1";
659 p2_alias_pub.publish(alias_id);
665 ASSERT_EQ(p1, p2) <<
"p2 is again the same person as p1";
669 person_ids.ids = {
"p2" };
670 person_pub.publish(person_ids);
675 <<
"the aliased person should have been deleted with its alias";
692 hri_listener.
onFace(face_callback.AsStdFunction());
694 testing::MockFunction<void(
ID)> face_lost_callback;
695 hri_listener.
onFaceLost(face_lost_callback.AsStdFunction());
699 hri_listener.
onBody(body_callback.AsStdFunction());
701 testing::MockFunction<void(
ID)> body_lost_callback;
702 hri_listener.
onBodyLost(body_lost_callback.AsStdFunction());
706 hri_listener.
onVoice(voice_callback.AsStdFunction());
708 testing::MockFunction<void(
ID)> voice_lost_callback;
709 hri_listener.
onVoiceLost(voice_lost_callback.AsStdFunction());
713 hri_listener.
onPerson(person_callback.AsStdFunction());
718 testing::MockFunction<void(
ID)> person_tracked_lost_callback;
723 auto ids = hri_msgs::IdsList();
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);
733 uint32_t face_call_count = 0;
734 EXPECT_CALL(face_callback, Call(testing::_)).WillRepeatedly(
735 testing::InvokeWithoutArgs([&face_call_count](){ face_call_count++; }));
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++; }));
741 uint32_t body_call_count = 0;
742 EXPECT_CALL(body_callback, Call(testing::_)).WillRepeatedly(
743 testing::InvokeWithoutArgs([&body_call_count](){ body_call_count++; }));
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++; }));
749 uint32_t voice_call_count = 0;
750 EXPECT_CALL(voice_callback, Call(testing::_)).WillRepeatedly(
751 testing::InvokeWithoutArgs([&voice_call_count](){ voice_call_count++; }));
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++; }));
757 uint32_t person_call_count = 0;
758 EXPECT_CALL(person_callback, Call(testing::_)).WillRepeatedly(
759 testing::InvokeWithoutArgs([&person_call_count](){ person_call_count++; }));
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++; }));
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++; }));
772 face_lost_call_count = 0;
776 EXPECT_EQ(face_call_count, 1);
777 EXPECT_EQ(face_lost_call_count, 0);
781 face_lost_call_count = 0;
782 ids.ids = {
"id1",
"id2" };
783 face_pub.publish(ids);
785 EXPECT_EQ(face_call_count, 1);
786 EXPECT_EQ(face_lost_call_count, 0);
789 face_lost_call_count = 0;
790 ids.ids = {
"id3",
"id4" };
791 face_pub.publish(ids);
793 EXPECT_EQ(face_call_count, 2);
794 EXPECT_EQ(face_lost_call_count, 2);
797 body_lost_call_count = 0;
798 ids.ids = {
"id1",
"id2" };
799 body_pub.publish(ids);
801 EXPECT_EQ(body_call_count, 2);
802 EXPECT_EQ(body_lost_call_count, 0);
805 face_lost_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);
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);
818 face_lost_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);
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);
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);
838 EXPECT_EQ(voice_call_count, 2);
839 EXPECT_EQ(person_call_count, 2);
840 EXPECT_EQ(person_tracked_call_count, 2);
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);
860 auto person_ids = hri_msgs::IdsList();
861 person_ids.ids = {
"p1" };
862 person_pub.publish(person_ids);
864 auto face_ids = hri_msgs::IdsList();
865 face_ids.ids = {
"f1" };
866 face_pub.publish(face_ids);
870 auto softbiometrics_msg = hri_msgs::SoftBiometrics();
871 softbiometrics_msg.age = 45;
872 softbiometrics_msg.age_confidence = 0.8;
874 softbiometrics_msg.gender_confidence = 0.7;
875 softbiometrics_pub.publish(softbiometrics_msg);
877 auto face_id = std_msgs::String();
880 person_face_pub.publish(face_id);
886 ASSERT_EQ(
face->id(),
"f1");
888 ASSERT_TRUE(
face->age());
889 ASSERT_EQ(*(
face->age()), 45);
890 ASSERT_TRUE(
face->gender());
894 softbiometrics_pub.publish(softbiometrics_msg);
899 softbiometrics_msg.gender = hri_msgs::SoftBiometrics::UNDEFINED;
900 softbiometrics_pub.publish(softbiometrics_msg);
903 ASSERT_FALSE(
face->gender());
917 auto person_pub = nh.
advertise<hri_msgs::IdsList>(
"/humans/persons/tracked", 1);
918 auto engagement_pub =
921 auto person_ids = hri_msgs::IdsList();
922 person_ids.ids = {
"p1" };
923 person_pub.publish(person_ids);
929 engagement_pub.publish(msg);
934 ASSERT_TRUE(p->engagement_status());
938 engagement_pub.publish(msg);
943 msg.level = hri_msgs::EngagementLevel::UNKNOWN;
944 engagement_pub.publish(msg);
947 ASSERT_FALSE(p->engagement_status());
964 geometry_msgs::TransformStamped world_transform;
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;
974 geometry_msgs::TransformStamped p1_transform;
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;
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);
987 auto person_ids = hri_msgs::IdsList();
988 person_ids.ids = {
"p1" };
989 person_pub.publish(person_ids);
995 auto msg = std_msgs::Float32();
997 loc_confidence_pub.publish(msg);
1000 ASSERT_EQ(p->location_confidence(), 0.);
1001 ASSERT_FALSE(p->transform()) <<
"location confidence at 0, no transform should be available";
1004 loc_confidence_pub.publish(msg);
1007 ASSERT_EQ(p->location_confidence(), 0.5);
1009 ASSERT_FALSE(p->transform()) <<
"location confidence > 0 but no transform published yet -> no transform should be returned";
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);
1024 loc_confidence_pub.publish(msg);
1027 ASSERT_EQ(p->location_confidence(), 1.);
1028 ASSERT_TRUE(p->transform()) <<
"location confidence > 0 => a transform should be available";
1043 testing::MockFunction<void(
bool)> is_speaking_callback;
1044 testing::MockFunction<void(
string)> speech_callback;
1045 testing::MockFunction<void(
string)> incremental_speech_callback;
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());
1057 auto ids = hri_msgs::IdsList();
1058 auto is_speaking = std_msgs::Bool();
1059 auto speech = hri_msgs::LiveSpeech();
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);
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++; }));
1071 uint32_t speech_call_count = 0;
1072 EXPECT_CALL(speech_callback, Call(testing::_)).WillRepeatedly(
1073 testing::InvokeWithoutArgs([&speech_call_count](){ speech_call_count++; }));
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++; }));
1081 ids.ids = {
"id1" };
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);
1091 EXPECT_EQ(is_speaking_call_count, 1);
1092 EXPECT_EQ(speech_call_count, 0);
1093 EXPECT_EQ(incremental_speech_call_count, 0);
1095 is_speaking_call_count = 0;
1096 is_speaking.data =
false;
1097 is_speaking_pub.publish(is_speaking);
1099 EXPECT_EQ(is_speaking_call_count, 1);
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);
1108 EXPECT_EQ(is_speaking_call_count, 0);
1109 EXPECT_EQ(speech_call_count, 1);
1110 EXPECT_EQ(incremental_speech_call_count, 0);
1112 is_speaking_call_count = 0;
1113 speech_call_count = 0;
1114 incremental_speech_call_count = 0;
1116 speech.incremental =
"incremental sentence";
1117 speech_pub.publish(speech);
1119 EXPECT_EQ(is_speaking_call_count, 0);
1120 EXPECT_EQ(speech_call_count, 0);
1121 EXPECT_EQ(incremental_speech_call_count, 1);
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);
1130 EXPECT_EQ(is_speaking_call_count, 0);
1131 EXPECT_EQ(speech_call_count, 1);
1132 EXPECT_EQ(incremental_speech_call_count, 1);
1139 testing::InitGoogleTest(&argc, argv);
1144 return RUN_ALL_TESTS();