From e9b615f8c56fcf4cc8be37783fbc4aa9b9e138db Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Tue, 20 Aug 2024 09:13:52 -0700 Subject: [PATCH] Don't use c++20 stuff --- src/Camera/QGCCameraManager.cc | 11 +++++------ src/Vehicle/Vehicle.cc | 25 ++++++++++++------------- 2 files changed, 17 insertions(+), 19 deletions(-) diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index b3beca0f897..3934997ff0f 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -400,12 +400,11 @@ static void _requestCameraInfoMessageResultHandler(void* resultHandlerData, MAV_ if (result != MAV_RESULT_ACCEPTED) { qCDebug(CameraManagerLog) << "MAV_CMD_REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_INFORMATION failed. Falling back to MAV_CMD_REQUEST_CAMERA_INFORMATION. compId" << cameraInfo->compID << "Result:" << result << "FailureCode:" << failureCode; - Vehicle::MavCmdAckHandlerInfo_t ackHandlerInfo = { - .resultHandler = _requestCameraInfoCommandResultHandler, - .resultHandlerData = cameraInfo, - .progressHandler = nullptr, - .progressHandlerData = nullptr - }; + Vehicle::MavCmdAckHandlerInfo_t ackHandlerInfo; + ackHandlerInfo.resultHandler = _requestCameraInfoCommandResultHandler; + ackHandlerInfo.resultHandlerData = cameraInfo; + ackHandlerInfo.progressHandler = nullptr; + ackHandlerInfo.progressHandlerData = nullptr; cameraInfo->vehicle->sendMavCommandWithHandler(&ackHandlerInfo, cameraInfo->compID, MAV_CMD_REQUEST_CAMERA_INFORMATION, 1 /* request camera capabilities */); } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 243b1601126..58441aa861a 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -2855,19 +2855,18 @@ void Vehicle::_requestMessageWaitForMessageResultHandler(void* resultHandlerData void Vehicle::requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData, int compId, int messageId, float param1, float param2, float param3, float param4, float param5) { - RequestMessageInfo_t requestInfo = { - .vehicle = this, - .compId = compId, - .msgId = messageId, - .resultHandler = resultHandler, - .resultHandlerData = resultHandlerData, - }; - _requestMessageInfoMap[compId][messageId] = new RequestMessageInfo_t(requestInfo); - - Vehicle::MavCmdAckHandlerInfo_t handlerInfo = { - .resultHandler = _requestMessageCmdResultHandler, - .resultHandlerData = &requestInfo, - }; + auto requestMessageInfo = new RequestMessageInfo_t; + requestMessageInfo->vehicle = this; + requestMessageInfo->compId = compId; + requestMessageInfo->msgId = messageId; + requestMessageInfo->resultHandler = resultHandler; + requestMessageInfo->resultHandlerData = resultHandlerData; + + _requestMessageInfoMap[compId][messageId] = requestMessageInfo; + + Vehicle::MavCmdAckHandlerInfo_t handlerInfo; + handlerInfo.resultHandler = _requestMessageCmdResultHandler; + handlerInfo.resultHandlerData = requestMessageInfo; _sendMavCommandWorker(false, // commandInt false, // showError