From e64fcaf5a846da345058d2cb098c245ec29aff5e Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 31 Oct 2018 17:29:36 -0700 Subject: [PATCH] [rcl_action] Bugfix: check if number of elements to allocate for message is greater than zero --- rcl_action/include/rcl_action/types.h | 12 ++++++---- rcl_action/src/rcl_action/types.c | 10 ++++++++ rcl_action/test/rcl_action/test_types.cpp | 28 +++++++++++++++++++---- 3 files changed, 41 insertions(+), 9 deletions(-) diff --git a/rcl_action/include/rcl_action/types.h b/rcl_action/include/rcl_action/types.h index bb3ffae..0976c7b 100644 --- a/rcl_action/include/rcl_action/types.h +++ b/rcl_action/include/rcl_action/types.h @@ -162,7 +162,8 @@ rcl_action_get_zero_initialized_cancel_response(void); * * \param[out] status_array a preallocated, zero-initialized, goal status array message * to be initialized. - * \param[in] num_status the number of status messages to allocate space for + * \param[in] num_status the number of status messages to allocate space for. + * Must be greater than zero * \param[in] allocator a valid allocator * \return `RCL_RET_OK` if cancel response was initialized successfully, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or @@ -217,10 +218,10 @@ rcl_action_goal_status_array_fini( * * rcl_action_cancel_response_t cancel_response = * rcl_action_get_zero_initialized_cancel_response(); - * size_t num_goals = 10; + * size_t num_goals_canceling = 10; * ret = rcl_action_cancel_response_init( * &cancel_response, - * num_goals, + * num_goals_canceling, * rcl_get_default_allocator()); * // ... error handling, and when done processing response, finalize * ret = rcl_action_cancel_response_fini(&cancel_response, rcl_get_default_allocator()); @@ -237,7 +238,8 @@ rcl_action_goal_status_array_fini( * * \param[out] cancel_response a preallocated, zero-initialized, cancel response message * to be initialized. - * \param[in] num_goals the number of goals that are canceling to add to the response + * \param[in] num_goals_canceling the number of goals that are canceling to add to the response. + * Must be greater than zero * \param[in] allocator a valid allocator * \return `RCL_RET_OK` if cancel response was initialized successfully, or * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or @@ -250,7 +252,7 @@ RCL_WARN_UNUSED rcl_ret_t rcl_action_cancel_response_init( rcl_action_cancel_response_t * cancel_response, - const size_t num_goals, + const size_t num_goals_canceling, const rcl_allocator_t allocator); /// Finalize a rcl_action_cancel_response_t. diff --git a/rcl_action/src/rcl_action/types.c b/rcl_action/src/rcl_action/types.c index 4b5a57d..1dd14be 100644 --- a/rcl_action/src/rcl_action/types.c +++ b/rcl_action/src/rcl_action/types.c @@ -56,6 +56,11 @@ rcl_action_goal_status_array_init( { RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT); + // Size of array to allocate must be greater than 0 + if (0 == num_status) { + RCL_SET_ERROR_MSG("num_status must be greater than zero"); + return RCL_RET_INVALID_ARGUMENT; + } // Ensure status array is zero initialized if (status_array->status_list.size > 0) { RCL_SET_ERROR_MSG("status_array already inititalized"); @@ -93,6 +98,11 @@ rcl_action_cancel_response_init( { RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT); + // Size of array to allocate must be greater than 0 + if (0 == num_goals_canceling) { + RCL_SET_ERROR_MSG("num_goals_canceling must be greater than zero"); + return RCL_RET_INVALID_ARGUMENT; + } // Ensure cancel response is zero initialized if (cancel_response->goals_canceling.size > 0) { RCL_SET_ERROR_MSG("cancel_response already inititalized"); diff --git a/rcl_action/test/rcl_action/test_types.cpp b/rcl_action/test/rcl_action/test_types.cpp index 6659ae5..9db71bc 100644 --- a/rcl_action/test/rcl_action/test_types.cpp +++ b/rcl_action/test/rcl_action/test_types.cpp @@ -87,14 +87,24 @@ TEST(TestActionTypes, test_init_fini_goal_status_array) ASSERT_EQ(status_array.status_list.size, 0u); ret = rcl_action_goal_status_array_init(&status_array, num_status, invalid_allocator); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); + EXPECT_EQ(status_array.status_list.size, 0u); + EXPECT_EQ(status_array.status_list.data, nullptr); + + // Initialize with zero size + status_array = rcl_action_get_zero_initialized_goal_status_array(); + ASSERT_EQ(status_array.status_list.size, 0u); + ret = rcl_action_goal_status_array_init(&status_array, 0, rcl_get_default_allocator()); + EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); + EXPECT_EQ(status_array.status_list.size, 0u); + EXPECT_EQ(status_array.status_list.data, nullptr); // Initialize with valid arguments status_array = rcl_action_get_zero_initialized_goal_status_array(); ASSERT_EQ(status_array.status_list.size, 0u); ret = rcl_action_goal_status_array_init(&status_array, num_status, rcl_get_default_allocator()); EXPECT_EQ(ret, RCL_RET_OK); - EXPECT_EQ(num_status, status_array.status_list.size); - EXPECT_NE(nullptr, status_array.status_list.data); + EXPECT_EQ(status_array.status_list.size, num_status); + EXPECT_NE(status_array.status_list.data, nullptr); // Finalize with invalid status array ret = rcl_action_goal_status_array_fini(nullptr, rcl_get_default_allocator()); @@ -126,6 +136,16 @@ TEST(TestActionTypes, test_init_fini_cancel_response) ASSERT_EQ(cancel_response.goals_canceling.size, 0u); ret = rcl_action_cancel_response_init(&cancel_response, num_goals_canceling, invalid_allocator); EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); + EXPECT_EQ(cancel_response.goals_canceling.size, 0u); + EXPECT_EQ(cancel_response.goals_canceling.data, nullptr); + + // Initialize with zero size + cancel_response = rcl_action_get_zero_initialized_cancel_response(); + ASSERT_EQ(cancel_response.goals_canceling.size, 0u); + ret = rcl_action_cancel_response_init(&cancel_response, 0, rcl_get_default_allocator()); + EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT); + EXPECT_EQ(cancel_response.goals_canceling.size, 0u); + EXPECT_EQ(cancel_response.goals_canceling.data, nullptr); // Initialize with valid arguments cancel_response = rcl_action_get_zero_initialized_cancel_response(); @@ -135,8 +155,8 @@ TEST(TestActionTypes, test_init_fini_cancel_response) num_goals_canceling, rcl_get_default_allocator()); EXPECT_EQ(ret, RCL_RET_OK); - EXPECT_EQ(num_goals_canceling, cancel_response.goals_canceling.size); - EXPECT_NE(nullptr, cancel_response.goals_canceling.data); + EXPECT_EQ(cancel_response.goals_canceling.size, num_goals_canceling); + EXPECT_NE(cancel_response.goals_canceling.data, nullptr); // Finalize with invalid cancel response ret = rcl_action_cancel_response_fini(nullptr, rcl_get_default_allocator());