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 static const std::string CANOPEN_GETOBJECT_SERVICE_NAME{ "/prbt/driver/get_object" };
27 static const std::string CANOPEN_SETOBJECT_SERVICE_NAME{ "/prbt/driver/set_object" };
28 
29 static const std::string BRAKE_TEST_DURATION_OBJECT_INDEX{ "2060sub1" };
30 static const std::string START_BRAKE_TEST_OBJECT_INDEX{ "2060sub2" };
31 static const std::string BRAKE_TEST_STATUS_OBJECT_INDEX{ "2060sub3" };
32 
33 using canopen_chain_node::GetObjectRequest;
34 using canopen_chain_node::GetObjectResponse;
35 using canopen_chain_node::SetObjectRequest;
36 using canopen_chain_node::SetObjectResponse;
37 
39 {
40  get_obj_serv_ = nh_.advertiseService(CANOPEN_GETOBJECT_SERVICE_NAME, &CANOpenChainNodeMock::get_obj, this);
41  set_obj_serv_ = nh_.advertiseService(CANOPEN_SETOBJECT_SERVICE_NAME, &CANOpenChainNodeMock::set_obj, this);
42 
44 }
45 
47 {
48  using ::testing::_;
49  using ::testing::DoAll;
50  using ::testing::Field;
51  using ::testing::Return;
52  using ::testing::SetArgReferee;
53 
54  GetObjectResponse duration_resp;
55  duration_resp.success = true;
56  duration_resp.value = "1";
57 
58  SetObjectResponse start_resp;
59  start_resp.success = true;
60 
61  GetObjectResponse status_resp;
62  status_resp.success = true;
63  status_resp.value = "\x02";
64 
65  // Set response for service calls getting the brake_test_duration object
66  ON_CALL(*this, get_obj(Field(&GetObjectRequest::object, BRAKE_TEST_DURATION_OBJECT_INDEX), _))
67  .WillByDefault(DoAll(SetArgReferee<1>(duration_resp), Return(true)));
68 
69  // Set response for service calls setting the start_brake_test object
70  ON_CALL(*this, set_obj(Field(&SetObjectRequest::object, START_BRAKE_TEST_OBJECT_INDEX), _))
71  .WillByDefault(DoAll(SetArgReferee<1>(start_resp), Return(true)));
72 
73  // Set response for service calls getting the brake_test_status object
74  ON_CALL(*this, get_obj(Field(&GetObjectRequest::object, BRAKE_TEST_STATUS_OBJECT_INDEX), _))
75  .WillByDefault(DoAll(SetArgReferee<1>(status_resp), Return(true)));
76 }
77 
79 {
80  using ::testing::_;
81  using ::testing::AnyNumber;
82  using ::testing::Field;
83 
84  EXPECT_CALL(*this, get_obj(_, _)).Times(AnyNumber());
85  EXPECT_CALL(*this, set_obj(_, _)).Times(AnyNumber());
86 
87  // Gripper should not be called
88  EXPECT_CALL(*this, get_obj(Field(&GetObjectRequest::node, "gripper_joint"), _)).Times(0);
89 
90  EXPECT_CALL(*this, set_obj(Field(&SetObjectRequest::node, "gripper_joint"), _)).Times(0);
91 }
92 
94 {
97 }
98 
100 {
102 }
103 
105 {
107 }
108 
109 } // 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 Mon Feb 28 2022 23:14:34