canopen_chain_node_mock.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 <gmock/gmock.h>
19 
20 #include <ros/ros.h>
21 
23 
24 namespace prbt_hardware_support
25 {
26 
27 static const std::string CANOPEN_GETOBJECT_SERVICE_NAME{"/prbt/driver/get_object"};
28 static const std::string CANOPEN_SETOBJECT_SERVICE_NAME{"/prbt/driver/set_object"};
29 
30 static const std::string BRAKE_TEST_DURATION_OBJECT_INDEX{"2060sub1"};
31 static const std::string START_BRAKE_TEST_OBJECT_INDEX{"2060sub2"};
32 static const std::string BRAKE_TEST_STATUS_OBJECT_INDEX{"2060sub3"};
33 
34 using canopen_chain_node::GetObjectRequest;
35 using canopen_chain_node::GetObjectResponse;
36 using canopen_chain_node::SetObjectRequest;
37 using canopen_chain_node::SetObjectResponse;
38 
40 {
41  get_obj_serv_ = nh_.advertiseService(CANOPEN_GETOBJECT_SERVICE_NAME, &CANOpenChainNodeMock::get_obj, this);
42  set_obj_serv_ = nh_.advertiseService(CANOPEN_SETOBJECT_SERVICE_NAME, &CANOpenChainNodeMock::set_obj, this);
43 
45 }
46 
48 {
49  using ::testing::_;
50  using ::testing::DoAll;
51  using ::testing::Field;
52  using ::testing::Return;
53  using ::testing::SetArgReferee;
54 
55  GetObjectResponse duration_resp;
56  duration_resp.success = true;
57  duration_resp.value = "1";
58 
59  SetObjectResponse start_resp;
60  start_resp.success = true;
61 
62  GetObjectResponse status_resp;
63  status_resp.success = true;
64  status_resp.value = "\x02";
65 
66  // Set response for service calls getting the brake_test_duration object
67  ON_CALL(*this, get_obj(Field(&GetObjectRequest::object, BRAKE_TEST_DURATION_OBJECT_INDEX), _))
68  .WillByDefault(DoAll(SetArgReferee<1>(duration_resp), Return(true)));
69 
70  // Set response for service calls setting the start_brake_test object
71  ON_CALL(*this, set_obj(Field(&SetObjectRequest::object, START_BRAKE_TEST_OBJECT_INDEX), _))
72  .WillByDefault(DoAll(SetArgReferee<1>(start_resp), Return(true)));
73 
74  // Set response for service calls getting the brake_test_status object
75  ON_CALL(*this, get_obj(Field(&GetObjectRequest::object, BRAKE_TEST_STATUS_OBJECT_INDEX), _))
76  .WillByDefault(DoAll(SetArgReferee<1>(status_resp), Return(true)));
77 }
78 
80 {
81  using ::testing::_;
82  using ::testing::AnyNumber;
83  using ::testing::Field;
84 
85  EXPECT_CALL(*this, get_obj(_, _))
86  .Times(AnyNumber());
87  EXPECT_CALL(*this, set_obj(_, _))
88  .Times(AnyNumber());
89 
90  // Gripper should not be called
91  EXPECT_CALL(
92  *this, get_obj(Field(&GetObjectRequest::node, "gripper_joint"), _)
93  )
94  .Times(0);
95 
96  EXPECT_CALL(
97  *this, set_obj(Field(&SetObjectRequest::node, "gripper_joint"), _)
98  )
99  .Times(0);
100 }
101 
103 {
106 }
107 
109 {
111 }
112 
114 {
116 }
117 
118 
119 } // namespace prbt_hardware_support
void expectAnything()
Set expectations on all mock methods, that can be fullfilled in any case.
void shutdownSetService()
Un-advertise the set service.
static const std::string BRAKE_TEST_STATUS_OBJECT_INDEX
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void shutdownGetService()
Un-advertise the get service.
void setDefaultActions()
Set default actions on all expected service calls.
static const std::string CANOPEN_GETOBJECT_SERVICE_NAME
static const std::string CANOPEN_SETOBJECT_SERVICE_NAME
static const std::string BRAKE_TEST_DURATION_OBJECT_INDEX
static const std::string START_BRAKE_TEST_OBJECT_INDEX
CANOpenChainNodeMock()
Advertise get_object and set_object services for CANOpen objects and call setDefaultActions().


prbt_hardware_support
Author(s):
autogenerated on Tue Feb 2 2021 03:50:17