pilz_manipulator_mock.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2018 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 #ifndef PRBT_HARDWARE_SUPPORT_PILZ_MANIPULATOR_MOCK_H
19 #define PRBT_HARDWARE_SUPPORT_PILZ_MANIPULATOR_MOCK_H
20 
21 #include <ros/ros.h>
22 #include <gtest/gtest.h>
23 #include <gmock/gmock.h>
24 
25 #include <std_srvs/Trigger.h>
26 
35 {
36 public:
37  void advertiseHoldService(ros::NodeHandle nh, std::string hold_service_name);
38  void advertiseUnholdService(ros::NodeHandle nh, std::string unhold_service_name);
39  void advertiseHaltService(ros::NodeHandle nh, std::string halt_service_name);
40  void advertiseRecoverService(ros::NodeHandle nh, std::string recover_service_name);
41 
42  void advertiseServices(ros::NodeHandle nh, std::string hold_service_name, std::string unhold_service_name,
43  std::string halt_service_name, std::string recover_service_name);
44 
45  MOCK_METHOD2(holdCb, bool(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp));
46  MOCK_METHOD2(unholdCb, bool(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp));
47  MOCK_METHOD2(haltCb, bool(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp));
48  MOCK_METHOD2(recoverCb, bool(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp));
49 
50 private:
51  bool holdCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
52  bool unholdCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
53  bool haltCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
54  bool recoverCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp);
55 
60 };
61 
62 void ManipulatorMock::advertiseHoldService(ros::NodeHandle nh, std::string hold_service_name)
63 {
64  hold_srv_ = nh.advertiseService(hold_service_name, &ManipulatorMock::holdCb_internal, this);
65  ROS_DEBUG_NAMED("ManipulatorMock", "Advertised %s", hold_srv_.getService().c_str());
66 }
67 
68 void ManipulatorMock::advertiseUnholdService(ros::NodeHandle nh, std::string unhold_service_name)
69 {
70  unhold_srv_ = nh.advertiseService(unhold_service_name, &ManipulatorMock::unholdCb_internal, this);
71  ROS_DEBUG_NAMED("ManipulatorMock", "Advertised %s", unhold_srv_.getService().c_str());
72 }
73 
74 void ManipulatorMock::advertiseHaltService(ros::NodeHandle nh, std::string halt_service_name)
75 {
76  halt_srv_ = nh.advertiseService(halt_service_name, &ManipulatorMock::haltCb_internal, this);
77  ROS_DEBUG_NAMED("ManipulatorMock", "Advertised %s", halt_srv_.getService().c_str());
78 }
79 
80 void ManipulatorMock::advertiseRecoverService(ros::NodeHandle nh, std::string recover_service_name)
81 {
82  recover_srv_ = nh.advertiseService(recover_service_name, &ManipulatorMock::recoverCb_internal, this);
83  ROS_DEBUG_NAMED("ManipulatorMock", "Advertised %s", recover_srv_.getService().c_str());
84 }
85 
86 bool ManipulatorMock::holdCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp)
87 {
88  ROS_DEBUG_NAMED("ManipulatorMock", "Call to %s", hold_srv_.getService().c_str());
89  return holdCb(req, resp);
90 }
91 
92 bool ManipulatorMock::unholdCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp)
93 {
94  ROS_DEBUG_NAMED("ManipulatorMock", "Call to %s", unhold_srv_.getService().c_str());
95  return unholdCb(req, resp);
96 }
97 
98 bool ManipulatorMock::haltCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp)
99 {
100  ROS_DEBUG_NAMED("ManipulatorMock", "Call to %s", halt_srv_.getService().c_str());
101  return haltCb(req, resp);
102 }
103 
104 bool ManipulatorMock::recoverCb_internal(std_srvs::Trigger::Request& req, std_srvs::Trigger::Response& resp)
105 {
106  ROS_DEBUG_NAMED("ManipulatorMock", "Call to %s", recover_srv_.getService().c_str());
107  return recoverCb(req, resp);
108 }
109 
110 void ManipulatorMock::advertiseServices(ros::NodeHandle nh, std::string hold_service_name,
111  std::string unhold_service_name, std::string halt_service_name,
112  std::string recover_service_name)
113 {
114  advertiseHoldService(nh, hold_service_name);
115  advertiseUnholdService(nh, unhold_service_name);
116  advertiseHaltService(nh, halt_service_name);
117  advertiseRecoverService(nh, recover_service_name);
118 }
119 
120 #endif // PRBT_HARDWARE_SUPPORT_PILZ_MANIPULATOR_MOCK_H
ros::ServiceServer recover_srv_
Mocks the ROS Api of the manipulator relevant for stopping and holding.
ros::ServiceServer hold_srv_
bool holdCb_internal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
bool unholdCb_internal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void advertiseRecoverService(ros::NodeHandle nh, std::string recover_service_name)
ros::ServiceServer unhold_srv_
#define ROS_DEBUG_NAMED(name,...)
void advertiseServices(ros::NodeHandle nh, std::string hold_service_name, std::string unhold_service_name, std::string halt_service_name, std::string recover_service_name)
ros::ServiceServer halt_srv_
std::string getService() const
void advertiseHaltService(ros::NodeHandle nh, std::string halt_service_name)
void advertiseHoldService(ros::NodeHandle nh, std::string hold_service_name)
MOCK_METHOD2(holdCb, bool(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp))
void advertiseUnholdService(ros::NodeHandle nh, std::string unhold_service_name)
bool haltCb_internal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)
bool recoverCb_internal(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &resp)


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