unittest_system_info.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019 Pilz GmbH & Co. KG
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8 
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13 
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <string>
19 #include <vector>
20 #include <thread>
21 #include <atomic>
22 #include <memory>
23 
24 #include <gtest/gtest.h>
25 #include <gmock/gmock.h>
26 
27 #include <ros/ros.h>
28 #include <canopen_chain_node/GetObject.h>
29 #include <sensor_msgs/JointState.h>
30 
33 #include <pilz_testutils/async_test.h>
36 
38 {
39 using canopen_chain_node::GetObject;
40 using namespace prbt_support;
41 using namespace testing;
42 
43 static const std::string GET_OBJECT_TOPIC_NAME{ "get_object" };
44 static const std::string JOINT_STATES_TOPIC_NAME{ "joint_states" };
45 static constexpr unsigned int JOINT_STATES_TOPIC_QUEUE_SIZE{ 1 };
46 
52 class SystemInfoTests : public testing::Test, public testing::AsyncTest
53 {
54 public:
55  void SetUp() override;
56  void TearDown() override;
57 
58  void publishJointState();
59 
60 protected:
61  MOCK_METHOD2(executeGetObject, bool(GetObject::Request&, GetObject::Response&));
62 
63  void advertiseGetObjectService();
64 
65 protected:
66  // Needed so that service callback are proecessed. Otherwise test in which
67  // service are calls will hang.
68  ros::AsyncSpinner spinner_{ 2 };
69 
70  const std::vector<std::string> joint_names_{ "joint1", "joint2" };
72  std::thread publisher_thread_;
73  std::atomic_bool terminate_{ false };
74 };
75 
77 {
78  ros::NodeHandle driver_nh{ "/prbt/driver/" };
79  get_obj_service_ = driver_nh.advertiseService(GET_OBJECT_TOPIC_NAME, &SystemInfoTests::executeGetObject, this);
80 }
81 
83 {
84  spinner_.start();
85 
86  // Set joint names on parameter server
87  ros::NodeHandle driver_nh{ "/prbt/driver/" };
88  for (unsigned int i = 0; i < joint_names_.size(); ++i)
89  {
90  driver_nh.setParam("nodes/" + joint_names_.at(i) + "/id", static_cast<int>(i));
91  }
92 
93  publisher_thread_ = std::thread(&SystemInfoTests::publishJointState, this);
94  advertiseGetObjectService();
95 }
96 
98 {
99  if (publisher_thread_.joinable())
100  {
101  terminate_ = true;
102  publisher_thread_.join();
103  }
104 }
105 
107 {
108  ros::NodeHandle global_nh{ "/" };
109  ros::Publisher joint_state_pub =
110  global_nh.advertise<sensor_msgs::JointState>(JOINT_STATES_TOPIC_NAME, JOINT_STATES_TOPIC_QUEUE_SIZE);
111 
112  while (!terminate_ && ros::ok())
113  {
114  joint_state_pub.publish(sensor_msgs::JointState());
115  ros::Duration(0.5).sleep();
116  }
117 }
118 
122 TEST_F(SystemInfoTests, TestExceptions)
123 {
124  const std::string exp_msg{ "Test-Msg" };
125  std::shared_ptr<SystemInfoException> ex{ new SystemInfoException(exp_msg) };
126  EXPECT_TRUE(std::string(ex->what()) == exp_msg);
127 }
128 
133 TEST_F(SystemInfoTests, testNodeNamesMissing)
134 {
135  ros::NodeHandle nh{ "~" };
136  nh.deleteParam("/prbt/driver/nodes");
137  EXPECT_THROW(SystemInfo{ nh }, SystemInfoException);
138 }
139 
144 TEST_F(SystemInfoTests, testCANUpAndRunning)
145 {
146  // Make sure that no JointStates are published
147  terminate_ = true;
148  publisher_thread_.join();
149 
150  // Variable stating if the constructor is finished or not.
151  std::atomic_bool ctor_called{ false };
152  // Start thread which allows us to asynchronously call the constructor
153  std::thread async_ctor_call_thread = std::thread([this, &ctor_called]() {
154  ros::NodeHandle nh{ "~" };
155  SystemInfo info(nh);
156  ctor_called = true;
157  this->triggerClearEvent("ctor_called");
158  });
159 
160  // Wait a while and then check if constructor is still waiting for the topic.
162  ASSERT_FALSE(ctor_called) << "Ctor already finished although \"/joint_states\" topic not published yet";
163 
164  // Activate publishing of "/joint_states"
165  terminate_ = false;
166  publisher_thread_ = std::thread(&SystemInfoTests::publishJointState, this);
167  pilz_utils::waitForMessage<sensor_msgs::JointState>("/joint_states");
168  // Wait till constructor is finished
169  BARRIER("ctor_called");
170 
171  if (async_ctor_call_thread.joinable())
172  {
173  async_ctor_call_thread.join();
174  }
175 }
176 
181 TEST_F(SystemInfoTests, testCANServiceUpAndRunning)
182 {
183  // Make sure that no ros_canopen service "get_object" is advertised.
184  get_obj_service_.shutdown();
185 
186  // Variable stating if the constructor is finished or not.
187  std::atomic_bool ctor_called{ false };
188  // Start thread which allows us to asynchronously call the constructor
189  std::thread async_ctor_call_thread = std::thread([this, &ctor_called]() {
190  ros::NodeHandle nh{ "~" };
191  SystemInfo info(nh);
192  ctor_called = true;
193  this->triggerClearEvent("ctor_called");
194  });
195 
196  // Wait a while and then check if constructor is still waiting for the topic.
198  ASSERT_FALSE(ctor_called) << "Ctor already finished although \"get_object\" service not advertised yet";
199 
200  advertiseGetObjectService();
201  pilz_utils::waitForService("/prbt/driver/get_object");
202  // Wait till constructor is finished
203  BARRIER("ctor_called");
204 
205  if (async_ctor_call_thread.joinable())
206  {
207  async_ctor_call_thread.join();
208  }
209 }
210 
215 TEST_F(SystemInfoTests, testServiceResponseFalse)
216 {
217  EXPECT_CALL(*this, executeGetObject(_, _))
218  .Times(1)
219  .WillRepeatedly(testing::Invoke([](GetObject::Request& /*unused*/, GetObject::Response& res) {
220  res.success = false;
221  return true;
222  }));
223 
224  ros::NodeHandle nh{ "~" };
225  SystemInfo info{ nh };
226  EXPECT_THROW(info.getFirmwareVersions(), SystemInfoException);
227 }
228 
232 TEST_F(SystemInfoTests, testServiceFail)
233 {
234  EXPECT_CALL(*this, executeGetObject(_, _))
235  .Times(1)
236  .WillRepeatedly(
237  testing::Invoke([](GetObject::Request& /*unused*/, GetObject::Response& /*unused*/) { return false; }));
238 
239  ros::NodeHandle nh{ "~" };
240  SystemInfo info{ nh };
241  EXPECT_THROW(info.getFirmwareVersions(), SystemInfoException);
242 }
243 
248 TEST_F(SystemInfoTests, testGetFirmwareVersions)
249 {
250  ASSERT_EQ(2u, joint_names_.size()) << "Number of joints in test set-up have changed => Change expected version "
251  "container in test accordingly.";
252 
253  const FirmwareCont exp_versions{ { joint_names_.at(0), "100 Build:11158 Date:2018-06-07 16:49:55" },
254  { joint_names_.at(1), "101 Build:11158 Date:2018-06-07 16:49:55" } };
255 
256  EXPECT_CALL(*this, executeGetObject(_, _))
257  .Times(2)
258  .WillRepeatedly(testing::Invoke([exp_versions](GetObject::Request& req, GetObject::Response& res) {
259  res.value = exp_versions.at(req.node);
260  res.success = true;
261  return true;
262  }));
263 
264  // Check that returned versions from service are correct
265  ros::NodeHandle nh{ "~" };
266  SystemInfo info{ nh };
267  FirmwareCont actual_version_cont{ info.getFirmwareVersions() };
268  for (const auto& joint : joint_names_)
269  {
270  EXPECT_TRUE(actual_version_cont.find(joint) != actual_version_cont.cend()) << "No version for joint found";
271  EXPECT_EQ(exp_versions.at(joint), actual_version_cont.at(joint)) << "Expected and actual firmware version do not "
272  "match";
273  }
274 }
275 
280 TEST_F(SystemInfoTests, testGetFirmwareVersionsResizeTo40Chars)
281 {
282  ASSERT_EQ(2u, joint_names_.size()) << "Number of joints in test set-up have changed => Change expected version "
283  "container in test accordingly.";
284 
285  const FirmwareCont exp_versions{ { joint_names_.at(0), "100 Build:11158 Date:2018-06-07 16:49:55" },
286  { joint_names_.at(1), "101 Build:11158 Date:2018-06-07 16:49:55" } };
287 
288  EXPECT_CALL(*this, executeGetObject(_, _))
289  .Times(2)
290  .WillRepeatedly(testing::Invoke([exp_versions](GetObject::Request& req, GetObject::Response& res) {
291  res.value = exp_versions.at(req.node) + "AdditionalStuffWhichNeedsToBeRemoved";
292  res.success = true;
293  return true;
294  }));
295 
296  // Check that returned versions from service are correct
297  ros::NodeHandle nh{ "~" };
298  SystemInfo info{ nh };
299  FirmwareCont actual_version_cont{ info.getFirmwareVersions() };
300  for (const auto& joint : joint_names_)
301  {
302  EXPECT_TRUE(actual_version_cont.find(joint) != actual_version_cont.cend()) << "No version for joint found";
303  EXPECT_EQ(exp_versions.at(joint), actual_version_cont.at(joint)) << "Expected and actual firmware version do not "
304  "match";
305  }
306 }
307 
308 } // namespace system_info_tests
309 
310 int main(int argc, char* argv[])
311 {
312  ros::init(argc, argv, "system_info_test");
313  ros::NodeHandle nh;
314 
315  testing::InitGoogleTest(&argc, argv);
316  return RUN_ALL_TESTS();
317 }
system_info_tests::SystemInfoTests
Collection of tests checking the functionality of the SystemInfo class.
Definition: unittest_system_info.cpp:52
system_info_tests::SystemInfoTests::get_obj_service_
ros::ServiceServer get_obj_service_
Definition: unittest_system_info.cpp:71
ros::Publisher
system_info_tests::SystemInfoTests::SetUp
void SetUp() override
Definition: unittest_system_info.cpp:82
system_info_tests::SystemInfoTests::publishJointState
void publishJointState()
Definition: unittest_system_info.cpp:106
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
pilz_utils::DEFAULT_RETRY_TIMEOUT
static constexpr double DEFAULT_RETRY_TIMEOUT
ros.h
prbt_support::SystemInfo::getFirmwareVersions
FirmwareCont getFirmwareVersions()
Definition: system_info.cpp:74
ros::AsyncSpinner
system_info_exception.h
system_info_tests::JOINT_STATES_TOPIC_NAME
static const std::string JOINT_STATES_TOPIC_NAME
Definition: unittest_system_info.cpp:44
system_info_tests::SystemInfoTests::publisher_thread_
std::thread publisher_thread_
Definition: unittest_system_info.cpp:72
prbt_support::FirmwareCont
std::map< std::string, std::string > FirmwareCont
Definition: system_info.h:33
system_info_tests::JOINT_STATES_TOPIC_QUEUE_SIZE
static constexpr unsigned int JOINT_STATES_TOPIC_QUEUE_SIZE
Definition: unittest_system_info.cpp:45
wait_for_service.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
system_info_tests
Definition: unittest_system_info.cpp:37
ros::ok
ROSCPP_DECL bool ok()
EXPECT_TRUE
#define EXPECT_TRUE(args)
ros::ServiceServer
prbt_support
Definition: system_info.h:29
system_info.h
system_info_tests::TEST_F
TEST_F(SystemInfoTests, TestExceptions)
Tests that exception stores and returns correct error message.
Definition: unittest_system_info.cpp:122
system_info_tests::SystemInfoTests::TearDown
void TearDown() override
Definition: unittest_system_info.cpp:97
prbt_support::SystemInfoException
Exception thrown by the SystemInfo class in case of an error.
Definition: system_info_exception.h:28
pilz_utils::waitForService
static void waitForService(const std::string service_name, const double retry_timeout=DEFAULT_RETRY_TIMEOUT, const double msg_output_period=DEFAULT_MSG_OUTPUT_PERIOD)
ros::Duration::sleep
bool sleep() const
system_info_tests::SystemInfoTests::advertiseGetObjectService
void advertiseGetObjectService()
Definition: unittest_system_info.cpp:76
prbt_support::SystemInfo
Provides easy access to system information which are of importance when analyzing bugs.
Definition: system_info.h:39
main
int main(int argc, char *argv[])
Definition: unittest_system_info.cpp:310
wait_for_message.h
ros::Duration
system_info_tests::GET_OBJECT_TOPIC_NAME
static const std::string GET_OBJECT_TOPIC_NAME
Definition: unittest_system_info.cpp:43
EXPECT_EQ
#define EXPECT_EQ(a, b)
ros::NodeHandle


prbt_support
Author(s):
autogenerated on Sat Nov 25 2023 03:51:49