AP_DDS: use memset to initialise variable size array

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
This commit is contained in:
Rhys Mainwaring 2024-11-12 12:18:17 +00:00 committed by Peter Barker
parent e14045898d
commit 2bd4e15f76
1 changed files with 6 additions and 4 deletions

View File

@ -955,8 +955,9 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u
.type = UXR_REPLIER_ID .type = UXR_REPLIER_ID
}; };
uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U); const uint32_t reply_size = rcl_interfaces_srv_SetParameters_Response_size_of_topic(&set_parameter_response, 0U);
uint8_t reply_buffer[reply_size] {}; uint8_t reply_buffer[reply_size];
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
ucdrBuffer reply_ub; ucdrBuffer reply_ub;
ucdr_init_buffer(&reply_ub, reply_buffer, reply_size); 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 .type = UXR_REPLIER_ID
}; };
uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U); const uint32_t reply_size = rcl_interfaces_srv_GetParameters_Response_size_of_topic(&get_parameters_response, 0U);
uint8_t reply_buffer[reply_size] {}; uint8_t reply_buffer[reply_size];
memset(reply_buffer, 0, reply_size * sizeof(uint8_t));
ucdrBuffer reply_ub; ucdrBuffer reply_ub;
ucdr_init_buffer(&reply_ub, reply_buffer, reply_size); ucdr_init_buffer(&reply_ub, reply_buffer, reply_size);