24 #include <gtest/gtest.h>
25 #include <gmock/gmock.h>
28 #include <canopen_chain_node/GetObject.h>
29 #include <sensor_msgs/JointState.h>
33 #include <pilz_testutils/async_test.h>
39 using canopen_chain_node::GetObject;
41 using namespace testing;
55 void SetUp()
override;
56 void TearDown()
override;
58 void publishJointState();
61 MOCK_METHOD2(executeGetObject,
bool(GetObject::Request&, GetObject::Response&));
63 void advertiseGetObjectService();
70 const std::vector<std::string> joint_names_{
"joint1",
"joint2" };
73 std::atomic_bool terminate_{
false };
79 get_obj_service_ = driver_nh.advertiseService(
GET_OBJECT_TOPIC_NAME, &SystemInfoTests::executeGetObject,
this);
88 for (
unsigned int i = 0; i < joint_names_.size(); ++i)
90 driver_nh.setParam(
"nodes/" + joint_names_.at(i) +
"/id",
static_cast<int>(i));
94 advertiseGetObjectService();
99 if (publisher_thread_.joinable())
102 publisher_thread_.join();
112 while (!terminate_ &&
ros::ok())
114 joint_state_pub.
publish(sensor_msgs::JointState());
124 const std::string exp_msg{
"Test-Msg" };
136 nh.deleteParam(
"/prbt/driver/nodes");
148 publisher_thread_.join();
151 std::atomic_bool ctor_called{
false };
153 std::thread async_ctor_call_thread = std::thread([
this, &ctor_called]() {
157 this->triggerClearEvent(
"ctor_called");
162 ASSERT_FALSE(ctor_called) <<
"Ctor already finished although \"/joint_states\" topic not published yet";
167 pilz_utils::waitForMessage<sensor_msgs::JointState>(
"/joint_states");
169 BARRIER(
"ctor_called");
171 if (async_ctor_call_thread.joinable())
173 async_ctor_call_thread.join();
184 get_obj_service_.shutdown();
187 std::atomic_bool ctor_called{
false };
189 std::thread async_ctor_call_thread = std::thread([
this, &ctor_called]() {
193 this->triggerClearEvent(
"ctor_called");
198 ASSERT_FALSE(ctor_called) <<
"Ctor already finished although \"get_object\" service not advertised yet";
200 advertiseGetObjectService();
203 BARRIER(
"ctor_called");
205 if (async_ctor_call_thread.joinable())
207 async_ctor_call_thread.join();
217 EXPECT_CALL(*
this, executeGetObject(_, _))
219 .WillRepeatedly(testing::Invoke([](GetObject::Request& , GetObject::Response& res) {
234 EXPECT_CALL(*
this, executeGetObject(_, _))
237 testing::Invoke([](GetObject::Request& , GetObject::Response& ) {
return false; }));
250 ASSERT_EQ(2u, joint_names_.size()) <<
"Number of joints in test set-up have changed => Change expected version "
251 "container in test accordingly.";
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" } };
256 EXPECT_CALL(*
this, executeGetObject(_, _))
258 .WillRepeatedly(testing::Invoke([exp_versions](GetObject::Request& req, GetObject::Response& res) {
259 res.value = exp_versions.at(req.node);
268 for (
const auto& joint : joint_names_)
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 "
282 ASSERT_EQ(2u, joint_names_.size()) <<
"Number of joints in test set-up have changed => Change expected version "
283 "container in test accordingly.";
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" } };
288 EXPECT_CALL(*
this, executeGetObject(_, _))
290 .WillRepeatedly(testing::Invoke([exp_versions](GetObject::Request& req, GetObject::Response& res) {
291 res.value = exp_versions.at(req.node) +
"AdditionalStuffWhichNeedsToBeRemoved";
300 for (
const auto& joint : joint_names_)
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 "
310 int main(
int argc,
char* argv[])
312 ros::init(argc, argv,
"system_info_test");
315 testing::InitGoogleTest(&argc, argv);
316 return RUN_ALL_TESTS();