1-
1+ #pragma clang diagnostic push
2+ #pragma clang diagnostic ignored "-Wdeprecated-copy"
23#include < gmock/gmock.h>
4+ #pragma clang diagnostic pop
35
46#include " dynamic_graph_bridge/ros.hpp"
57#include " dynamic_graph_bridge/sot_loader.hh"
8+ #include " dynamic_graph_bridge_msgs/msg/vector.hpp"
9+ #include " test_common.hpp"
10+
11+ namespace test_sot_loader {
12+ int l_argc;
13+ char ** l_argv;
14+ }
15+
16+ namespace dg = dynamicgraph;
617
718class MockSotLoaderTest : public ::testing::Test {
819 public:
920 class MockSotLoader : public SotLoader {
1021 public:
22+ rclcpp::Subscription<dynamic_graph_bridge_msgs::msg::Vector>::SharedPtr
23+ subscription_;
24+
1125 ~MockSotLoader () {}
1226
27+ void topic_callback (const dynamic_graph_bridge_msgs::msg::Vector::SharedPtr msg) const {
28+ auto lsize=msg->data .size ();
29+ }
30+
31+ void subscribe_to_a_topic () {
32+ subscription_ = create_subscription<dynamic_graph_bridge_msgs::msg::Vector>(
33+ " control_ros" , 1 , std::bind (&MockSotLoader::topic_callback, this ,
34+ std::placeholders::_1));
35+ }
36+
1337 void generateEvents () {
1438 usleep (20000 );
1539 std::cerr << " Start Dynamic Graph " << std::endl;
@@ -33,6 +57,7 @@ class MockSotLoaderTest : public ::testing::Test {
3357 std::string finalname (" libimpl_test_library.so" );
3458 EXPECT_TRUE (finalname == dynamicLibraryName_);
3559
60+ readSotVectorStateParam ();
3661 // Performs initialization of libimpl_test_library.so
3762 loadController ();
3863 EXPECT_TRUE (sotRobotControllerLibrary_ != 0 );
@@ -54,6 +79,14 @@ class MockSotLoaderTest : public ::testing::Test {
5479 // Start the thread generating events.
5580 std::thread local_events (&MockSotLoader::generateEvents, this );
5681
82+ // Create and call the clients.
83+ std::string file_name =
84+ TEST_CONFIG_PATH + std::string (" simple_ros_publish.py" );
85+ std::string result = " " ;
86+ std::string standard_output = " " ;
87+ std::string standard_error = " " ;
88+ // start_run_python_script_ros_service(file_name, result);
89+
5790 // Wait for each threads.
5891 SotLoader::lthread_join (); // Wait 100 ms
5992 local_events.join ();
@@ -63,6 +96,18 @@ class MockSotLoaderTest : public ::testing::Test {
6396 public:
6497 MockSotLoader *mockSotLoader_ptr_;
6598
99+ // For the set of tests coded in this file.
100+ static void SetUpTestCase () {
101+
102+ rclcpp::init (test_sot_loader::l_argc,
103+ test_sot_loader::l_argv);
104+ }
105+
106+ // For each test specified in this file
107+ static void TearDownTestCase () {
108+ rclcpp::shutdown ();
109+ }
110+
66111 void SetUp () {
67112 mockSotLoader_ptr_ = new MockSotLoader ();
68113 mockSotLoader_ptr_->initialize ();
@@ -80,10 +125,12 @@ TEST_F(MockSotLoaderTest, TestLoadController) {
80125
81126int main (int argc, char **argv) {
82127 ::testing::InitGoogleTest (&argc, argv);
83- rclcpp::init (argc, argv);
128+
129+ test_sot_loader::l_argc = argc;
130+ test_sot_loader::l_argv = argv;
131+
84132
85133 int r = RUN_ALL_TESTS ();
86134
87- rclcpp::shutdown ();
88135 return r;
89136}
0 commit comments