18 #include <gmock/gmock.h> 33 using canopen_chain_node::GetObjectRequest;
34 using canopen_chain_node::GetObjectResponse;
35 using canopen_chain_node::SetObjectRequest;
36 using canopen_chain_node::SetObjectResponse;
49 using ::testing::DoAll;
50 using ::testing::Field;
51 using ::testing::Return;
52 using ::testing::SetArgReferee;
54 GetObjectResponse duration_resp;
55 duration_resp.success =
true;
56 duration_resp.value =
"1";
58 SetObjectResponse start_resp;
59 start_resp.success =
true;
61 GetObjectResponse status_resp;
62 status_resp.success =
true;
63 status_resp.value =
"\x02";
67 .WillByDefault(DoAll(SetArgReferee<1>(duration_resp), Return(
true)));
71 .WillByDefault(DoAll(SetArgReferee<1>(start_resp), Return(
true)));
75 .WillByDefault(DoAll(SetArgReferee<1>(status_resp), Return(
true)));
81 using ::testing::AnyNumber;
82 using ::testing::Field;
84 EXPECT_CALL(*
this, get_obj(_, _)).Times(AnyNumber());
85 EXPECT_CALL(*
this, set_obj(_, _)).Times(AnyNumber());
88 EXPECT_CALL(*
this, get_obj(Field(&GetObjectRequest::node,
"gripper_joint"), _)).Times(0);
90 EXPECT_CALL(*
this, set_obj(Field(&SetObjectRequest::node,
"gripper_joint"), _)).Times(0);
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.
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.
ros::ServiceServer get_obj_serv_
void shutdown()
Un-advertise services.
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().