29 #include <gtest/gtest.h> 30 #include <gmock/gmock.h> 34 using ::testing::Invoke;
43 ON_CALL(*
this, activate(_,_,_))
45 ON_CALL(*
this, close(_))
47 ON_CALL(*
this, getCurrents(_,_,_))
49 ON_CALL(*
this, getDeviceIds(_,_))
51 ON_CALL(*
this, getInfo(_,_,_,_))
53 ON_CALL(*
this, getMeasurements(_,_,_))
55 ON_CALL(*
this, getParameters(_,_,_,_,_,_,_))
57 ON_CALL(*
this, getSerialPorts(_))
59 ON_CALL(*
this, getStatus(_,_,_))
61 ON_CALL(*
this, open(_,_))
63 ON_CALL(*
this, setInputs(_,_,_))
67 MOCK_METHOD3(activate,
void(comm_settings *file_descriptor,
int id,
char activate_command));
68 MOCK_METHOD1(close,
void(comm_settings *file_descriptor));
69 MOCK_METHOD3(getCurrents,
int(comm_settings *file_descriptor,
int id,
short int currents[2]));
70 MOCK_METHOD2(getDeviceIds,
int(comm_settings *file_descriptor,
char device_ids[255]));
71 MOCK_METHOD4(getInfo,
int(comm_settings *file_descriptor,
int id,
short int info_type,
char *info));
72 MOCK_METHOD3(getMeasurements,
int(comm_settings *file_descriptor,
int id,
short int measurements[3]));
73 MOCK_METHOD7(getParameters,
int(comm_settings *file_descriptor,
int id,
unsigned short index,
void *values,
74 unsigned short value_size,
unsigned short num_of_values, uint8_t *buffer));
75 MOCK_METHOD1(getSerialPorts,
int(
char serial_ports[10][255]));
76 MOCK_METHOD3(getStatus,
int(comm_settings *file_descriptor,
int id,
char *activate_status));
77 MOCK_METHOD2(open,
void(comm_settings *file_descriptor,
const char *serial_port));
78 MOCK_METHOD3(setInputs,
void(comm_settings *file_descriptor,
int id,
short int inputs[]));
80 void realActivate(comm_settings *file_descriptor,
int id,
char activate_command) {
81 qbDeviceAPI::activate(file_descriptor,
id, activate_command);
84 qbDeviceAPI::close(file_descriptor);
86 int realGetCurrents(comm_settings *file_descriptor,
int id,
short int currents[2]) {
87 return qbDeviceAPI::getCurrents(file_descriptor,
id, currents);
90 return qbDeviceAPI::getDeviceIds(file_descriptor, device_ids);
92 int realGetInfo(comm_settings *file_descriptor,
int id,
short int info_type,
char *info) {
93 return qbDeviceAPI::getInfo(file_descriptor,
id, info_type, info);
96 return qbDeviceAPI::getMeasurements(file_descriptor,
id, measurements);
98 int realGetParameters(comm_settings *file_descriptor,
int id,
unsigned short index,
void *values,
99 unsigned short value_size,
unsigned short num_of_values, uint8_t *buffer) {
100 return qbDeviceAPI::getParameters(file_descriptor,
id, index, values, value_size, num_of_values, buffer);
103 return qbDeviceAPI::getSerialPorts(serial_ports);
105 int realGetStatus(comm_settings *file_descriptor,
int id,
char *activate_status) {
106 return qbDeviceAPI::getStatus(file_descriptor,
id, activate_status);
108 void realOpen(comm_settings *file_descriptor,
const char *serial_port) {
109 qbDeviceAPI::open(file_descriptor, serial_port);
111 void realSetInputs(comm_settings *file_descriptor,
int id,
short int inputs[]) {
112 qbDeviceAPI::setInputs(file_descriptor,
id, inputs);
124 ON_CALL(*
this, activate())
125 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realActivate));
126 ON_CALL(*
this, close())
127 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realClose));
128 ON_CALL(*
this, deactivate())
129 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realDeactivate));
130 ON_CALL(*
this,
get(_,_))
131 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realGet));
132 ON_CALL(*
this, getInfo())
133 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realGetInfo));
134 ON_CALL(*
this, isActive())
135 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realIsActive));
136 ON_CALL(*
this, isOpen())
137 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realIsOpen));
138 ON_CALL(*
this, open())
139 .WillByDefault(Invoke(
this,
static_cast<int (
qbDeviceHWMock::*)()
>(&qbDeviceHWMock::realOpen)));
141 .WillByDefault(Invoke(
this,
static_cast<int (
qbDeviceHWMock::*)(
const std::string&)
>(&qbDeviceHWMock::realOpen)));
142 ON_CALL(*
this, retrieveDeviceParameters(_,_))
143 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realRetrieveDeviceParameters));
144 ON_CALL(*
this, retrieveSerialPort())
145 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realRetrieveSerialPort));
146 ON_CALL(*
this,
set(_))
147 .WillByDefault(Invoke(
this, &qbDeviceHWMock::realSet));
150 MOCK_METHOD0(activate,
int());
151 MOCK_METHOD0(close,
int());
152 MOCK_METHOD0(deactivate,
int());
153 MOCK_METHOD2(
get,
int(std::vector<double> &positions, std::vector<double> ¤ts));
154 MOCK_METHOD0(getInfo, std::string());
155 MOCK_METHOD0(isActive,
bool());
156 MOCK_METHOD0(isOpen,
bool());
157 MOCK_METHOD0(open,
int());
158 MOCK_METHOD1(open,
int(
const std::string &serial_port));
159 MOCK_METHOD2(retrieveDeviceParameters,
int(std::vector<int> &limits, std::vector<int> &resolutions));
160 MOCK_METHOD0(retrieveSerialPort,
int());
161 MOCK_METHOD1(
set,
int(
const std::vector<double> &commands));
164 return qbDeviceHW::activate();
167 return qbDeviceHW::close();
170 return qbDeviceHW::deactivate();
172 int realGet(std::vector<double> &positions, std::vector<double> ¤ts) {
173 return qbDeviceHW::get(positions, currents);
176 return qbDeviceHW::getInfo();
179 return qbDeviceHW::isActive();
182 return qbDeviceHW::isOpen();
185 return qbDeviceHW::open();
188 return qbDeviceHW::open(serial_port);
191 return qbDeviceHW::retrieveDeviceParameters(limits, resolutions);
194 return qbDeviceHW::retrieveSerialPort();
196 int realSet(
const std::vector<double> &commands) {
197 return qbDeviceHW::set(commands);
int realGetParameters(comm_settings *file_descriptor, int id, unsigned short index, void *values, unsigned short value_size, unsigned short num_of_values, uint8_t *buffer)
MOCK_METHOD3(activate, void(comm_settings *file_descriptor, int id, char activate_command))
void realActivate(comm_settings *file_descriptor, int id, char activate_command)
int realGetMeasurements(comm_settings *file_descriptor, int id, short int measurements[3])
int realGetInfo(comm_settings *file_descriptor, int id, short int info_type, char *info)
MOCK_METHOD2(getDeviceIds, int(comm_settings *file_descriptor, char device_ids[255]))
qbDeviceHWMock(qb_device_driver::qbDeviceAPIPtr api_mock)
int realGetDeviceIds(comm_settings *file_descriptor, char device_ids[255])
int realSet(const std::vector< double > &commands)
void realOpen(comm_settings *file_descriptor, const char *serial_port)
int realRetrieveDeviceParameters(std::vector< int > &limits, std::vector< int > &resolutions)
MOCK_METHOD7(getParameters, int(comm_settings *file_descriptor, int id, unsigned short index, void *values, unsigned short value_size, unsigned short num_of_values, uint8_t *buffer))
int realOpen(const std::string &serial_port)
void realSetInputs(comm_settings *file_descriptor, int id, short int inputs[])
int realRetrieveSerialPort()
The qbrobotics Device HardWare interface extends the hardware_interface::RobotHW by providing all the...
MOCK_METHOD4(getInfo, int(comm_settings *file_descriptor, int id, short int info_type, char *info))
std::shared_ptr< qbDeviceAPIMock > qbDeviceAPIMockPtr
MOCK_METHOD1(close, void(comm_settings *file_descriptor))
int realGetStatus(comm_settings *file_descriptor, int id, char *activate_status)
std::string realGetInfo()
int realGet(std::vector< double > &positions, std::vector< double > ¤ts)
int realGetCurrents(comm_settings *file_descriptor, int id, short int currents[2])
int realGetSerialPorts(char serial_ports[10][255])
void realClose(comm_settings *file_descriptor)