From 57716039643bddc4cee455d33b3b09138568c358 Mon Sep 17 00:00:00 2001 From: Guillaume Sarthou Date: Wed, 26 Jun 2024 18:05:16 +0200 Subject: [PATCH] [Ci] update CI --- src/test/CI/action_pub_sub.cpp | 76 +++++++++++++++++++--------------- src/test/CI/fact_pub_sub.cpp | 58 +++++++++++++++----------- src/test/occasions_sub_pub.cpp | 43 +++++++++++-------- 3 files changed, 101 insertions(+), 76 deletions(-) diff --git a/src/test/CI/action_pub_sub.cpp b/src/test/CI/action_pub_sub.cpp index 5a43090..4854711 100644 --- a/src/test/CI/action_pub_sub.cpp +++ b/src/test/CI/action_pub_sub.cpp @@ -1,13 +1,11 @@ -#include - -#include - #include +#include +#include -#include "ontologenius/OntologyManipulator.h" -#include "mementar/API/mementar/TimelineManipulator.h" -#include "mementar/API/mementar/OccasionsSubscriber.h" #include "mementar/API/mementar/ActionsSubscriber.h" +#include "mementar/API/mementar/OccasionsSubscriber.h" +#include "mementar/API/mementar/TimelineManipulator.h" +#include "ontologenius/OntologyManipulator.h" mementar::TimelineManipulator* time_ptr; @@ -47,17 +45,18 @@ TEST(action_pub_sub_tests, TimelineManipulator_fact_start_subscriber) r.sleep(); for(size_t i = 0; i < 2; i++) { - time_ptr->action_feeder.insert("act_" + std::to_string(i)); - time_ptr->action_feeder.insert("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("other_act_" + std::to_string(i)); } for(size_t i = 0; i < 2; i++) { - time_ptr->action_feeder.insertEnd("act_" + std::to_string(i)); - time_ptr->action_feeder.insertEnd("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("other_act_" + std::to_string(i)); } r.sleep(); - EXPECT_TRUE((cpt_fact_start == 1) && (cpt_fact_end == 0)); + EXPECT_EQ(cpt_fact_start, 1); + EXPECT_EQ(cpt_fact_end, 0); } TEST(action_pub_sub_tests, TimelineManipulator_fact_end_subscriber) @@ -71,17 +70,18 @@ TEST(action_pub_sub_tests, TimelineManipulator_fact_end_subscriber) r.sleep(); for(size_t i = 10; i < 12; i++) { - time_ptr->action_feeder.insert("act_" + std::to_string(i)); - time_ptr->action_feeder.insert("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("other_act_" + std::to_string(i)); } for(size_t i = 10; i < 12; i++) { - time_ptr->action_feeder.insertEnd("act_" + std::to_string(i)); - time_ptr->action_feeder.insertEnd("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("other_act_" + std::to_string(i)); } r.sleep(); - EXPECT_TRUE((cpt_fact_start == 0) && (cpt_fact_end == 1)); + EXPECT_EQ(cpt_fact_start, 0); + EXPECT_EQ(cpt_fact_end, 1); } TEST(action_pub_sub_tests, TimelineManipulator_action_start_subscriber) @@ -95,17 +95,18 @@ TEST(action_pub_sub_tests, TimelineManipulator_action_start_subscriber) r.sleep(); for(size_t i = 20; i < 22; i++) { - time_ptr->action_feeder.insert("act_" + std::to_string(i)); - time_ptr->action_feeder.insert("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("other_act_" + std::to_string(i)); } for(size_t i = 20; i < 22; i++) { - time_ptr->action_feeder.insertEnd("act_" + std::to_string(i)); - time_ptr->action_feeder.insertEnd("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("other_act_" + std::to_string(i)); } r.sleep(); - EXPECT_TRUE((cpt_act_start == 1) && (cpt_act_end == 0)); + EXPECT_EQ(cpt_act_start, 1); + EXPECT_EQ(cpt_act_end, 0); } TEST(action_pub_sub_tests, TimelineManipulator_action_end_subscriber) @@ -119,17 +120,18 @@ TEST(action_pub_sub_tests, TimelineManipulator_action_end_subscriber) r.sleep(); for(size_t i = 30; i < 32; i++) { - time_ptr->action_feeder.insert("act_" + std::to_string(i)); - time_ptr->action_feeder.insert("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("act_" + std::to_string(i)); + time_ptr->action_feeder_.insert("other_act_" + std::to_string(i)); } for(size_t i = 30; i < 32; i++) { - time_ptr->action_feeder.insertEnd("act_" + std::to_string(i)); - time_ptr->action_feeder.insertEnd("other_act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("act_" + std::to_string(i)); + time_ptr->action_feeder_.insertEnd("other_act_" + std::to_string(i)); } r.sleep(); - EXPECT_TRUE((cpt_act_start == 0) && (cpt_act_end == 1)); + EXPECT_EQ(cpt_act_start, 0); + EXPECT_EQ(cpt_act_end, 1); } TEST(action_pub_sub_tests, TimelineManipulator_action_start_end_subscriber) @@ -145,27 +147,33 @@ TEST(action_pub_sub_tests, TimelineManipulator_action_start_end_subscriber) r.sleep(); for(size_t i = 40; i < 42; i++) { - time_ptr->action_feeder.insert("act_" + std::to_string(i), time(0), time(0) + 2); - time_ptr->action_feeder.insert("other_act_" + std::to_string(i), time(0), time(0) + 2); + time_ptr->action_feeder_.insert("act_" + std::to_string(i), time(0), time(0) + 2); + time_ptr->action_feeder_.insert("other_act_" + std::to_string(i), time(0), time(0) + 2); } r.sleep(); - EXPECT_TRUE((cpt_act_start == 1) && (cpt_act_end == 1)); + EXPECT_EQ(cpt_act_start, 1); + EXPECT_EQ(cpt_act_end, 1); } int main(int argc, char** argv) { ros::init(argc, argv, "action_pub_sub_tests"); - ros::NodeHandle n; + // std::thread th([]() { mementar::compat::mem_ros::Node::get().spin(); }); + std::thread th([]() { ros::spin(); }); + onto::OntologyManipulator onto; - mementar::TimelineManipulator timeline(&n); + mementar::TimelineManipulator timeline; + timeline.waitInit(); time_ptr = &timeline; onto.close(); testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); - return 0; + // mementar::compat::mem_ros::Node::shutdown(); + // th.join(); + + return RUN_ALL_TESTS(); } diff --git a/src/test/CI/fact_pub_sub.cpp b/src/test/CI/fact_pub_sub.cpp index 99c036c..332942d 100644 --- a/src/test/CI/fact_pub_sub.cpp +++ b/src/test/CI/fact_pub_sub.cpp @@ -1,12 +1,10 @@ -#include - -#include - #include +#include +#include -#include "ontologenius/OntologyManipulator.h" -#include "include/mementar/API/mementar/TimelineManipulator.h" #include "include/mementar/API/mementar/OccasionsSubscriber.h" +#include "include/mementar/API/mementar/TimelineManipulator.h" +#include "ontologenius/OntologyManipulator.h" onto::OntologyManipulator* onto_ptr; mementar::TimelineManipulator* time_ptr; @@ -42,12 +40,13 @@ TEST(fact_pub_sub_tests, TimelineManipulator_one_subscriber) r.sleep(); for(size_t i = 0; i < 5; i++) { - time_ptr->fact_feeder.insert(mementar::Fact("a", "b", "c")); - time_ptr->fact_feeder.insert(mementar::Fact("d", "e", "f")); + time_ptr->fact_feeder_.insert(mementar::Fact("a", "b", "c")); + time_ptr->fact_feeder_.insert(mementar::Fact("d", "e", "f")); } r.sleep(); - EXPECT_TRUE((cpt_abc == 3) && (cpt_def == 0)); + EXPECT_EQ(cpt_abc, 3); + EXPECT_EQ(cpt_def, 0); } TEST(fact_pub_sub_tests, TimelineManipulator_two_subscriber) @@ -63,12 +62,13 @@ TEST(fact_pub_sub_tests, TimelineManipulator_two_subscriber) r.sleep(); for(size_t i = 0; i < 5; i++) { - time_ptr->fact_feeder.insert(mementar::Fact("a", "b", "c")); - time_ptr->fact_feeder.insert(mementar::Fact("d", "e", "f")); + time_ptr->fact_feeder_.insert(mementar::Fact("a", "b", "c")); + time_ptr->fact_feeder_.insert(mementar::Fact("d", "e", "f")); } r.sleep(); - EXPECT_TRUE((cpt_abc == 4) && (cpt_def == 1)); + EXPECT_EQ(cpt_abc, 4); + EXPECT_EQ(cpt_def, 1); } TEST(fact_pub_sub_tests, TimelineManipulator_three_subscriber) @@ -85,12 +85,13 @@ TEST(fact_pub_sub_tests, TimelineManipulator_three_subscriber) r.sleep(); for(size_t i = 0; i < 5; i++) { - time_ptr->fact_feeder.insert(mementar::Fact("a", "b", "c")); - time_ptr->fact_feeder.insert(mementar::Fact("d", "e", "f")); + time_ptr->fact_feeder_.insert(mementar::Fact("a", "b", "c")); + time_ptr->fact_feeder_.insert(mementar::Fact("d", "e", "f")); } r.sleep(); - EXPECT_TRUE((cpt_abc == 6) && (cpt_def == 1)); + EXPECT_EQ(cpt_abc, 6); + EXPECT_EQ(cpt_def, 1); } TEST(fact_pub_sub_tests, TimelineManipulator_pattern_subscriber) @@ -104,12 +105,13 @@ TEST(fact_pub_sub_tests, TimelineManipulator_pattern_subscriber) r.sleep(); for(size_t i = 0; i < 5; i++) { - time_ptr->fact_feeder.insert(mementar::Fact("a", "b", "c")); - time_ptr->fact_feeder.insert(mementar::Fact("a", "b", "d")); + time_ptr->fact_feeder_.insert(mementar::Fact("a", "b", "c")); + time_ptr->fact_feeder_.insert(mementar::Fact("a", "b", "d")); } r.sleep(); - EXPECT_TRUE((cpt_abc == 10) && (cpt_def == 0)); + EXPECT_EQ(cpt_abc, 10); + EXPECT_EQ(cpt_def, 0); } TEST(fact_pub_sub_tests, OntologyManipulator_one_subscriber) @@ -117,6 +119,7 @@ TEST(fact_pub_sub_tests, OntologyManipulator_one_subscriber) ros::Rate r(0.9); onto_ptr->feeder.addInheritage("a", "cube"); onto_ptr->feeder.removeProperty("a", "b", "c"); + onto_ptr->feeder.waitUpdate(1500); mementar::OccasionsSubscriber sub1(&factCallbackABC); sub1.subscribe(mementar::Fact("a", "b", "c"), 1); @@ -127,7 +130,8 @@ TEST(fact_pub_sub_tests, OntologyManipulator_one_subscriber) onto_ptr->feeder.addProperty("a", "b", "c"); r.sleep(); - EXPECT_TRUE((cpt_abc == 1) && (cpt_def == 0)); + EXPECT_EQ(cpt_abc, 1); + EXPECT_EQ(cpt_def, 0); } TEST(fact_pub_sub_tests, OntologyManipulator_inv_subscriber) @@ -135,6 +139,7 @@ TEST(fact_pub_sub_tests, OntologyManipulator_inv_subscriber) ros::Rate r(0.9); onto_ptr->feeder.addInheritage("a", "cube"); onto_ptr->feeder.removeProperty("a", "isOn", "c"); + onto_ptr->feeder.waitUpdate(1500); mementar::OccasionsSubscriber sub1(&factCallbackCisUnderA); sub1.subscribe(mementar::Fact("c", "isUnder", "a"), 1); @@ -144,23 +149,28 @@ TEST(fact_pub_sub_tests, OntologyManipulator_inv_subscriber) onto_ptr->feeder.addProperty("a", "isOn", "c"); r.sleep(); - EXPECT_TRUE(cpt_cIsUndera == 1); + EXPECT_EQ(cpt_cIsUndera, 1); } int main(int argc, char** argv) { ros::init(argc, argv, "fact_pub_sub_tests"); - ros::NodeHandle n; + // std::thread th([]() { mementar::compat::mem_ros::Node::get().spin(); }); + std::thread th([]() { ros::spin(); }); + onto::OntologyManipulator onto; onto_ptr = &onto; - mementar::TimelineManipulator timeline(&n); + mementar::TimelineManipulator timeline; + timeline.waitInit(); time_ptr = &timeline; onto.close(); testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); - return 0; + // mementar::compat::mem_ros::Node::shutdown(); + // th.join(); + + return RUN_ALL_TESTS(); } diff --git a/src/test/occasions_sub_pub.cpp b/src/test/occasions_sub_pub.cpp index c1af680..be8a935 100644 --- a/src/test/occasions_sub_pub.cpp +++ b/src/test/occasions_sub_pub.cpp @@ -1,23 +1,24 @@ -#include #include +#include +#include +#include -#include "ros/ros.h" - +#include "mementar/API/mementar/Fact.h" +#include "mementar/API/mementar/OccasionsSubscriber.h" +#include "mementar/API/mementar/TimelineManipulator.h" +#include "mementar/compat/ros.h" #include "ontologenius/OntologyManipulator.h" -#include "include/mementar/API/mementar/TimelineManipulator.h" -#include "include/mementar/API/mementar/OccasionsSubscriber.h" - using namespace std::chrono; high_resolution_clock::time_point t1, t2; -void callback_1(const mementar::Fact& fct) +void callback1(const mementar::Fact& fct) { std::cout << "[CB1] " << fct() << std::endl; } -void callback_2(const mementar::Fact& fct) +void callback2(const mementar::Fact& fct) { std::cout << "[CB2] " << fct() << std::endl; } @@ -30,19 +31,19 @@ void ontoCallback(const mementar::Fact& fct) int main(int argc, char** argv) { - ros::init(argc, argv, "occasions_sub_pub"); + mementar::compat::mem_ros::Node::init(argc, argv, "occasions_sub_pub"); + std::thread th([]() { mementar::compat::mem_ros::Node::get().spin(); }); - ros::NodeHandle n; onto::OntologyManipulator onto; - mementar::TimelineManipulator manip(&n); + mementar::TimelineManipulator manip; manip.waitInit(); std::cout << "init" << std::endl; - mementar::OccasionsSubscriber sub1(&callback_1, true); + mementar::OccasionsSubscriber sub1(&callback1); sub1.subscribe(mementar::Fact("bob", "eat", "?"), 2); - mementar::OccasionsSubscriber sub2(&callback_2, true); + mementar::OccasionsSubscriber sub2(&callback2); sub2.subscribe(mementar::Fact("max", "eat", "?"), 3); sub2.subscribe(mementar::Fact("bob", "eat", "?"), 4); @@ -65,7 +66,7 @@ int main(int argc, char** argv) { onto.feeder.waitConnected(); - mementar::OccasionsSubscriber onto_sub(&ontoCallback, true); + mementar::OccasionsSubscriber onto_sub(&ontoCallback); onto_sub.subscribe(mementar::Fact("onto", "isA", "Ontology"), 1); for(size_t i = 0; i < 100; i++) @@ -73,25 +74,31 @@ int main(int argc, char** argv) onto.feeder.addConcept("onto"); onto.feeder.addProperty("onto", "isA", "Ontology"); + onto.feeder.waitUpdate(1500); t1 = high_resolution_clock::now(); - while(!onto_sub.end() && ros::ok()) + while(!onto_sub.end() && mementar::compat::mem_ros::Node::ok()) r.sleep(); duration time_span = duration_cast>(t2 - t1); std::cout << "callback in " << time_span.count() << std::endl; onto_sub.subscribe(mementar::Fact("oro", "isUnder", "onto"), 1); - onto.feeder.addProperty("onto", "isOn", "oro"); + onto.feeder.addProperty("onto", "isOnTopOf", "oro"); + onto.feeder.waitUpdate(1500); t1 = high_resolution_clock::now(); - while(!onto_sub.end() && ros::ok()) + while(!onto_sub.end() && mementar::compat::mem_ros::Node::ok()) r.sleep(); time_span = duration_cast>(t2 - t1); std::cout << "callback in " << time_span.count() << std::endl; - onto.feeder.removeProperty("onto", "isOn", "oro"); + onto.feeder.removeProperty("onto", "isOnTopOf", "oro"); + onto.feeder.waitUpdate(1500); } + mementar::compat::mem_ros::Node::shutdown(); + th.join(); + return 0; }