Skip to content

Commit 1cf03a4

Browse files
Lobotuerkahcorde
authored andcommitted
Add tests service/client request/response with bad arguments (#141)
Signed-off-by: lobotuerk <[email protected]>
1 parent 8eca818 commit 1cf03a4

File tree

2 files changed

+257
-0
lines changed

2 files changed

+257
-0
lines changed

test_rmw_implementation/test/test_client.cpp

Lines changed: 105 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -204,3 +204,108 @@ TEST_F(CLASSNAME(TestClientUse, RMW_IMPLEMENTATION), destroy_client_of_another_i
204204
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
205205
rmw_reset_error();
206206
}
207+
208+
TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), send_request_with_bad_arguments) {
209+
constexpr char service_name[] = "/test";
210+
const rosidl_service_type_support_t * ts =
211+
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
212+
test_msgs__srv__BasicTypes_Request client_request;
213+
ASSERT_TRUE(test_msgs__srv__BasicTypes_Request__init(&client_request));
214+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
215+
{
216+
test_msgs__srv__BasicTypes_Request__fini(&client_request);
217+
});
218+
client_request.bool_value = false;
219+
client_request.uint8_value = 1;
220+
client_request.uint32_value = 2;
221+
int64_t sequence_number;
222+
rmw_client_t * client =
223+
rmw_create_client(node, ts, service_name, &rmw_qos_profile_default);
224+
ASSERT_NE(nullptr, client) << rmw_get_error_string().str;
225+
226+
rmw_ret_t ret = rmw_send_request(nullptr, &client_request, &sequence_number);
227+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
228+
rmw_reset_error();
229+
230+
ret = rmw_send_request(client, nullptr, &sequence_number);
231+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
232+
rmw_reset_error();
233+
234+
ret = rmw_send_request(client, &client_request, nullptr);
235+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
236+
rmw_reset_error();
237+
238+
const char * implementation_identifier = client->implementation_identifier;
239+
client->implementation_identifier = "not-an-rmw-implementation-identifier";
240+
ret = rmw_send_request(client, &client_request, &sequence_number);
241+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret) << rmw_get_error_string().str;
242+
rmw_reset_error();
243+
client->implementation_identifier = implementation_identifier;
244+
245+
ret = rmw_destroy_client(node, client);
246+
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
247+
rmw_reset_error();
248+
}
249+
250+
TEST_F(CLASSNAME(TestClient, RMW_IMPLEMENTATION), take_response_with_bad_arguments) {
251+
constexpr char service_name[] = "/test";
252+
const rosidl_service_type_support_t * ts =
253+
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
254+
test_msgs__srv__BasicTypes_Request client_request;
255+
ASSERT_TRUE(test_msgs__srv__BasicTypes_Request__init(&client_request));
256+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
257+
{
258+
test_msgs__srv__BasicTypes_Request__fini(&client_request);
259+
});
260+
client_request.bool_value = false;
261+
client_request.uint8_value = 1;
262+
client_request.uint32_value = 2;
263+
bool taken = false;
264+
rmw_service_info_t header;
265+
rmw_client_t * client =
266+
rmw_create_client(node, ts, service_name, &rmw_qos_profile_default);
267+
ASSERT_NE(nullptr, client) << rmw_get_error_string().str;
268+
269+
rmw_ret_t ret = rmw_take_response(nullptr, &header, &client_request, &taken);
270+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
271+
EXPECT_EQ(false, client_request.bool_value); // Verify post conditions
272+
EXPECT_EQ(1u, client_request.uint8_value);
273+
EXPECT_EQ(2u, client_request.uint32_value);
274+
EXPECT_EQ(false, taken);
275+
rmw_reset_error();
276+
277+
ret = rmw_take_response(client, nullptr, &client_request, &taken);
278+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
279+
EXPECT_EQ(false, client_request.bool_value); // Verify post conditions
280+
EXPECT_EQ(1u, client_request.uint8_value);
281+
EXPECT_EQ(2u, client_request.uint32_value);
282+
EXPECT_EQ(false, taken);
283+
rmw_reset_error();
284+
285+
ret = rmw_take_response(client, &header, nullptr, &taken);
286+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
287+
EXPECT_EQ(false, taken);
288+
rmw_reset_error();
289+
290+
ret = rmw_take_response(client, &header, &client_request, nullptr);
291+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
292+
EXPECT_EQ(false, client_request.bool_value); // Verify post conditions
293+
EXPECT_EQ(1u, client_request.uint8_value);
294+
EXPECT_EQ(2u, client_request.uint32_value);
295+
rmw_reset_error();
296+
297+
const char * implementation_identifier = client->implementation_identifier;
298+
client->implementation_identifier = "not-an-rmw-implementation-identifier";
299+
ret = rmw_take_response(client, &header, &client_request, &taken);
300+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret) << rmw_get_error_string().str;
301+
EXPECT_EQ(false, client_request.bool_value); // Verify post conditions
302+
EXPECT_EQ(1u, client_request.uint8_value);
303+
EXPECT_EQ(2u, client_request.uint32_value);
304+
EXPECT_EQ(false, taken);
305+
rmw_reset_error();
306+
client->implementation_identifier = implementation_identifier;
307+
308+
ret = rmw_destroy_client(node, client);
309+
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
310+
rmw_reset_error();
311+
}

test_rmw_implementation/test/test_service.cpp

Lines changed: 152 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -204,3 +204,155 @@ TEST_F(CLASSNAME(TestServiceUse, RMW_IMPLEMENTATION), destroy_service_of_another
204204
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
205205
rmw_reset_error();
206206
}
207+
208+
TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), take_request_with_bad_arguments) {
209+
constexpr char service_name[] = "/test";
210+
const rosidl_service_type_support_t * ts =
211+
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
212+
test_msgs__srv__BasicTypes_Request service_request;
213+
ASSERT_TRUE(test_msgs__srv__BasicTypes_Request__init(&service_request));
214+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
215+
{
216+
test_msgs__srv__BasicTypes_Request__fini(&service_request);
217+
});
218+
service_request.bool_value = false;
219+
service_request.uint8_value = 1;
220+
service_request.uint32_value = 2;
221+
bool taken = false;
222+
rmw_service_info_t header;
223+
rmw_service_t * srv =
224+
rmw_create_service(node, ts, service_name, &rmw_qos_profile_default);
225+
ASSERT_NE(nullptr, srv) << rmw_get_error_string().str;
226+
227+
rmw_ret_t ret = rmw_take_request(nullptr, &header, &service_request, &taken);
228+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
229+
EXPECT_EQ(false, service_request.bool_value); // Verify post conditions
230+
EXPECT_EQ(1u, service_request.uint8_value);
231+
EXPECT_EQ(2u, service_request.uint32_value);
232+
EXPECT_EQ(false, taken);
233+
rmw_reset_error();
234+
235+
ret = rmw_take_request(srv, nullptr, &service_request, &taken);
236+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
237+
EXPECT_EQ(false, service_request.bool_value); // Verify post conditions
238+
EXPECT_EQ(1u, service_request.uint8_value);
239+
EXPECT_EQ(2u, service_request.uint32_value);
240+
EXPECT_EQ(false, taken);
241+
rmw_reset_error();
242+
243+
ret = rmw_take_request(srv, &header, nullptr, &taken);
244+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
245+
EXPECT_EQ(false, taken);
246+
rmw_reset_error();
247+
248+
ret = rmw_take_request(srv, &header, &service_request, nullptr);
249+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
250+
EXPECT_EQ(false, service_request.bool_value); // Verify post conditions
251+
EXPECT_EQ(1u, service_request.uint8_value);
252+
EXPECT_EQ(2u, service_request.uint32_value);
253+
rmw_reset_error();
254+
255+
const char * implementation_identifier = srv->implementation_identifier;
256+
srv->implementation_identifier = "not-an-rmw-implementation-identifier";
257+
ret = rmw_take_request(srv, &header, &service_request, &taken);
258+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret) << rmw_get_error_string().str;
259+
EXPECT_EQ(false, service_request.bool_value); // Verify post conditions
260+
EXPECT_EQ(1u, service_request.uint8_value);
261+
EXPECT_EQ(2u, service_request.uint32_value);
262+
EXPECT_EQ(false, taken);
263+
rmw_reset_error();
264+
srv->implementation_identifier = implementation_identifier;
265+
266+
ret = rmw_destroy_service(node, srv);
267+
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
268+
rmw_reset_error();
269+
}
270+
271+
TEST_F(CLASSNAME(TestService, RMW_IMPLEMENTATION), send_reponse_with_bad_arguments) {
272+
constexpr char service_name[] = "/test";
273+
const rosidl_service_type_support_t * ts =
274+
ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes);
275+
test_msgs__srv__BasicTypes_Response service_response;
276+
ASSERT_TRUE(test_msgs__srv__BasicTypes_Response__init(&service_response));
277+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
278+
{
279+
test_msgs__srv__BasicTypes_Response__fini(&service_response);
280+
});
281+
service_response.bool_value = false;
282+
service_response.uint8_value = 1;
283+
service_response.uint32_value = 2;
284+
test_msgs__srv__BasicTypes_Request request;
285+
ASSERT_TRUE(test_msgs__srv__BasicTypes_Request__init(&request));
286+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
287+
{
288+
test_msgs__srv__BasicTypes_Request__fini(&request);
289+
});
290+
request.bool_value = false;
291+
request.uint8_value = 1;
292+
request.uint32_value = 2;
293+
int64_t sequence_number;
294+
rmw_service_info_t header;
295+
rmw_service_t * srv =
296+
rmw_create_service(node, ts, service_name, &rmw_qos_profile_default);
297+
ASSERT_NE(nullptr, srv) << rmw_get_error_string().str;
298+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
299+
{
300+
rmw_ret_t ret = rmw_destroy_service(node, srv);
301+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
302+
});
303+
rmw_client_t * client =
304+
rmw_create_client(node, ts, service_name, &rmw_qos_profile_default);
305+
ASSERT_NE(nullptr, client) << rmw_get_error_string().str;
306+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
307+
{
308+
rmw_ret_t ret = rmw_destroy_client(node, client);
309+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
310+
});
311+
312+
rmw_ret_t ret = rmw_send_request(client, &request, &sequence_number);
313+
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
314+
315+
size_t number_of_services = 1u;
316+
rmw_wait_set_t * wait_set = rmw_create_wait_set(&context, number_of_services);
317+
ASSERT_NE(nullptr, wait_set) << rmw_get_error_string().str;
318+
OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT(
319+
{
320+
rmw_ret_t ret = rmw_destroy_wait_set(wait_set);
321+
EXPECT_EQ(RMW_RET_OK, ret) << rcutils_get_error_string().str;
322+
});
323+
void * array[1];
324+
array[0] = srv->data;
325+
rmw_services_t srv_array;
326+
srv_array.service_count = 1u;
327+
srv_array.services = array;
328+
rmw_time_t timeout;
329+
timeout.sec = 0;
330+
timeout.nsec = rmw_intraprocess_discovery_delay.count() * 1000;
331+
ret = rmw_wait(nullptr, nullptr, &srv_array, nullptr, nullptr, wait_set, &timeout);
332+
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
333+
ASSERT_NE(nullptr, srv_array.services[0]);
334+
335+
bool taken = false;
336+
ret = rmw_take_request(srv, &header, &request, &taken);
337+
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
338+
ASSERT_EQ(true, taken);
339+
340+
ret = rmw_send_response(nullptr, &header.request_id, &service_response);
341+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
342+
rmw_reset_error();
343+
344+
ret = rmw_send_response(srv, nullptr, &service_response);
345+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
346+
rmw_reset_error();
347+
348+
ret = rmw_send_response(srv, &header.request_id, nullptr);
349+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
350+
rmw_reset_error();
351+
352+
const char * implementation_identifier = srv->implementation_identifier;
353+
srv->implementation_identifier = "not-an-rmw-implementation-identifier";
354+
ret = rmw_send_response(srv, &header.request_id, &service_response);
355+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret) << rmw_get_error_string().str;
356+
rmw_reset_error();
357+
srv->implementation_identifier = implementation_identifier;
358+
}

0 commit comments

Comments
 (0)