Skip to content

Commit

Permalink
AP_DDS: use memset to initialise variable size array
Browse files Browse the repository at this point in the history
Signed-off-by: Rhys Mainwaring <[email protected]>
  • Loading branch information
srmainwaring authored and peterbarker committed Nov 12, 2024
1 parent e140458 commit 2bd4e15
Showing 1 changed file with 6 additions and 4 deletions.
10 changes: 6 additions & 4 deletions libraries/AP_DDS/AP_DDS_Client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -955,8 +955,9 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
.type = UXR_REPLIER_ID
};

uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
uint8_t reply_buffer[reply_size] {};
const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
uint8_t reply_buffer[reply_size];
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
ucdrBuffer reply_ub;

ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);
Expand Down Expand Up @@ -1040,8 +1041,9 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
.type = UXR_REPLIER_ID
};

uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U);
uint8_t reply_buffer[reply_size] {};
const uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U);
uint8_t reply_buffer[reply_size];
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
ucdrBuffer reply_ub;

ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);
Expand Down

0 comments on commit 2bd4e15

Please sign in to comment.