1
-
1
+ #pragma clang diagnostic push
2
+ #pragma clang diagnostic ignored "-Wdeprecated-copy"
2
3
#include < gmock/gmock.h>
4
+ #pragma clang diagnostic pop
3
5
4
6
#include " dynamic_graph_bridge/ros.hpp"
5
7
#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;
6
17
7
18
class MockSotLoaderTest : public ::testing::Test {
8
19
public:
9
20
class MockSotLoader : public SotLoader {
10
21
public:
22
+ rclcpp::Subscription<dynamic_graph_bridge_msgs::msg::Vector>::SharedPtr
23
+ subscription_;
24
+
11
25
~MockSotLoader () {}
12
26
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
+
13
37
void generateEvents () {
14
38
usleep (20000 );
15
39
std::cerr << " Start Dynamic Graph " << std::endl;
@@ -33,6 +57,7 @@ class MockSotLoaderTest : public ::testing::Test {
33
57
std::string finalname (" libimpl_test_library.so" );
34
58
EXPECT_TRUE (finalname == dynamicLibraryName_);
35
59
60
+ readSotVectorStateParam ();
36
61
// Performs initialization of libimpl_test_library.so
37
62
loadController ();
38
63
EXPECT_TRUE (sotRobotControllerLibrary_ != 0 );
@@ -54,6 +79,14 @@ class MockSotLoaderTest : public ::testing::Test {
54
79
// Start the thread generating events.
55
80
std::thread local_events (&MockSotLoader::generateEvents, this );
56
81
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
+
57
90
// Wait for each threads.
58
91
SotLoader::lthread_join (); // Wait 100 ms
59
92
local_events.join ();
@@ -63,6 +96,18 @@ class MockSotLoaderTest : public ::testing::Test {
63
96
public:
64
97
MockSotLoader *mockSotLoader_ptr_;
65
98
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
+
66
111
void SetUp () {
67
112
mockSotLoader_ptr_ = new MockSotLoader ();
68
113
mockSotLoader_ptr_->initialize ();
@@ -80,10 +125,12 @@ TEST_F(MockSotLoaderTest, TestLoadController) {
80
125
81
126
int main (int argc, char **argv) {
82
127
::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
+
84
132
85
133
int r = RUN_ALL_TESTS ();
86
134
87
- rclcpp::shutdown ();
88
135
return r;
89
136
}
0 commit comments