18 #ifndef PRBT_HARDWARE_SUPPORT_CANOPEN_CHAIN_NODE_MOCK_H 19 #define PRBT_HARDWARE_SUPPORT_CANOPEN_CHAIN_NODE_MOCK_H 21 #include <gtest/gtest.h> 22 #include <gmock/gmock.h> 25 #include <canopen_chain_node/GetObject.h> 26 #include <canopen_chain_node/SetObject.h> 68 MOCK_METHOD2(get_obj,
bool(canopen_chain_node::GetObjectRequest&, canopen_chain_node::GetObjectResponse&));
69 MOCK_METHOD2(set_obj,
bool(canopen_chain_node::SetObjectRequest&, canopen_chain_node::SetObjectResponse&));
void expectAnything()
Set expectations on all mock methods, that can be fullfilled in any case.
ros::ServiceServer set_obj_serv_
void shutdownSetService()
Un-advertise the set service.
void shutdownGetService()
Un-advertise the get service.
ros::ServiceServer get_obj_serv_
MOCK_METHOD2(get_obj, bool(canopen_chain_node::GetObjectRequest &, canopen_chain_node::GetObjectResponse &))
void shutdown()
Un-advertise services.
void setDefaultActions()
Set default actions on all expected service calls.
CANOpenChainNodeMock()
Advertise get_object and set_object services for CANOpen objects and call setDefaultActions().