18 #ifndef PRBT_HARDWARE_SUPPORT_PILZ_MANIPULATOR_MOCK_H 19 #define PRBT_HARDWARE_SUPPORT_PILZ_MANIPULATOR_MOCK_H 22 #include <gtest/gtest.h> 23 #include <gmock/gmock.h> 25 #include <std_srvs/Trigger.h> 43 std::string halt_service_name, std::string recover_service_name);
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));
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);
89 return holdCb(req, resp);
95 return unholdCb(req, resp);
101 return haltCb(req, resp);
107 return recoverCb(req, resp);
111 std::string unhold_service_name, std::string halt_service_name,
112 std::string recover_service_name)
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)