unittest_disable_speed_monitoring.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 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 
20 #include <gtest/gtest.h>
21 #include <gmock/gmock.h>
22 
23 #include <ros/ros.h>
24 
25 #include <std_srvs/SetBool.h>
26 
27 #include <pilz_testutils/async_test.h>
28 
30 {
31 static const std::string SPEED_MONITOR_SERVICE_NAME{ "/prbt/manipulator_joint_trajectory_controller/"
32  "monitor_cartesian_speed" };
33 
34 static const std::string SPEED_MONITOR_CALLBACK_EVENT{ "speed_monitor_callback" };
35 
37 {
38 public:
39  MOCK_METHOD2(callback, bool(std_srvs::SetBool::Request&, std_srvs::SetBool::Response&));
40 };
41 
42 class DisableSpeedMonitoringTest : public testing::Test, public testing::AsyncTest
43 {
44 };
45 
52 TEST_F(DisableSpeedMonitoringTest, testDisableSpeedMonitoring)
53 {
54  using testing::_;
55  using testing::Field;
56  using testing::Return;
57  using testing::SetArgReferee;
58 
59  ros::NodeHandle nh;
60  SpeedMonitorServiceMock service_mock;
61 
62  std_srvs::SetBoolResponse response;
63  response.success = true;
64 
65  ON_CALL(service_mock, callback(_, _)).WillByDefault(DoAll(SetArgReferee<1>(response), Return(true)));
66 
67  EXPECT_CALL(service_mock, callback(Field(&std_srvs::SetBoolRequest::data, false), _))
68  .WillOnce(DoAll(SetArgReferee<1>(response), ACTION_OPEN_BARRIER(SPEED_MONITOR_CALLBACK_EVENT)));
69 
70  ros::ServiceServer speed_monitor_srv =
71  nh.advertiseService(SPEED_MONITOR_SERVICE_NAME, &SpeedMonitorServiceMock::callback, &service_mock);
72 
74 }
75 
76 } // namespace disable_speed_monitoring_tests
77 
78 int main(int argc, char** argv)
79 {
80  ros::init(argc, argv, "unittest_disable_speed_monitoring");
81  ros::NodeHandle nh;
82 
84  spinner.start();
85 
86  testing::InitGoogleTest(&argc, argv);
87  return RUN_ALL_TESTS();
88 }
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void spinner()
MOCK_METHOD2(callback, bool(std_srvs::SetBool::Request &, std_srvs::SetBool::Response &))
TEST_F(DisableSpeedMonitoringTest, testDisableSpeedMonitoring)
const std::string response


prbt_hardware_support
Author(s):
autogenerated on Mon Feb 28 2022 23:14:34