From 2bd4e15f761d7263e3eb41d0557eb9ea6b6c1d27 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Tue, 12 Nov 2024 12:18:17 +0000 Subject: [PATCH] AP_DDS: use memset to initialise variable size array Signed-off-by: Rhys Mainwaring --- libraries/AP_DDS/AP_DDS_Client.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index b70c026b6a..05ba28f06d 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -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); @@ -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);