diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 825624e83b7d6b030a258cbc0c9c7d6df81f4437..9c0837d26ba74a86324c1cf338838c20ac91e277 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -602,15 +602,12 @@ void APMSensorsComponentController::cancelCalibration(void) void APMSensorsComponentController::nextClicked(void) { mavlink_message_t msg; - mavlink_command_ack_t ack; - - ack.command = 0; - ack.result = 1; - mavlink_msg_command_ack_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), - qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), - _vehicle->priorityLink()->mavlinkChannel(), - &msg, - &ack); + mavlink_msg_command_ack_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), + qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), + _vehicle->priorityLink()->mavlinkChannel(), + &msg, + 0, // command + 1); // result _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 30d4ac195be39b41c7ca174526d01c304ebf19a3..09ff4157b9ff4a78a4069417ed5a9d19d03a677e 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -666,6 +666,8 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN mavlink_param_set_t p; mavlink_param_union_t union_value; + memset(&p, 0, sizeof(p)); + FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type(); p.param_type = _factTypeToMavType(factType); @@ -786,6 +788,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian // Return the hash value to notify we don't want any more updates mavlink_param_set_t p; mavlink_param_union_t union_value; + memset(&p, 0, sizeof(p)); p.param_type = MAV_PARAM_TYPE_UINT32; strncpy(p.param_id, "_HASH_CHECK", sizeof(p.param_id)); union_value.param_uint32 = crc32_value; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 284ca89df013303f9fa6f198a4acc9db4874f21c..3987eeff945da9da05a40afdf2f7150491fabebe 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -228,6 +228,8 @@ void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle* vehicle, mavlink_mess mavlink_param_value_t paramValue; mavlink_param_union_t paramUnion; + memset(¶mValue, 0, sizeof(paramValue)); + // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what // type they are. Fix that up to correct usage. @@ -278,6 +280,8 @@ void APMFirmwarePlugin::_handleOutgoingParamSet(Vehicle* vehicle, LinkInterface* mavlink_param_set_t paramSet; mavlink_param_union_t paramUnion; + memset(¶mSet, 0, sizeof(paramSet)); + // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what // type they are. Fix it back to the wrong way on the way out. diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 2fb2b2a0303e3f566e4216d701e2676031c8bafd..ca33b2e5dde4c3d553b28252198abc91a048a4d9 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -184,7 +184,7 @@ void ArduCopterFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double mavlink_message_t msg; mavlink_set_position_target_local_ned_t cmd; - memset(&cmd, 0, sizeof(mavlink_set_position_target_local_ned_t)); + memset(&cmd, 0, sizeof(cmd)); cmd.target_system = vehicle->id(); cmd.target_component = vehicle->defaultComponentId(); diff --git a/src/FollowMe/FollowMe.cc b/src/FollowMe/FollowMe.cc index 0681ca2bdfddfcd415017e1f152a5733118058a7..ae18e8ecd71be1aad2cafb463e7e38bee2d2e315 100644 --- a/src/FollowMe/FollowMe.cc +++ b/src/FollowMe/FollowMe.cc @@ -119,7 +119,7 @@ void FollowMe::_sendGCSMotionReport(void) MAVLinkProtocol* mavlinkProtocol = _toolbox->mavlinkProtocol(); mavlink_follow_target_t follow_target; - memset(&follow_target, 0, sizeof(mavlink_follow_target_t)); + memset(&follow_target, 0, sizeof(follow_target)); follow_target.timestamp = runTime.nsecsElapsed()*1e-6; follow_target.est_capabilities = estimatation_capabilities; diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index f24b67a38dd2c2f5318433be936341b43b0e280c..08337448ab31a83b0bfd0a534c8f464c669c9ea0 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -110,6 +110,7 @@ void MissionManager::_writeMissionCount(void) mavlink_message_t message; mavlink_mission_count_t missionCount; + memset(&missionCount, 0, sizeof(missionCount)); missionCount.target_system = _vehicle->id(); missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.count = _missionItems.count(); @@ -137,6 +138,7 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC mavlink_message_t messageOut; mavlink_mission_item_t missionItem; + memset(&missionItem, 8, sizeof(missionItem)); missionItem.target_system = _vehicle->id(); missionItem.target_component = _vehicle->defaultComponentId(); missionItem.seq = 0; @@ -191,6 +193,8 @@ void MissionManager::_requestList(void) mavlink_message_t message; mavlink_mission_request_list_t request; + memset(&request, 0, sizeof(request)); + _itemIndicesToRead.clear(); _clearMissionItems(); @@ -306,6 +310,8 @@ void MissionManager::_readTransactionComplete(void) mavlink_message_t message; mavlink_mission_ack_t missionAck; + + memset(&missionAck, 0, sizeof(missionAck)); missionAck.target_system = _vehicle->id(); missionAck.target_component = MAV_COMP_ID_MISSIONPLANNER; @@ -360,6 +366,7 @@ void MissionManager::_requestNextMissionItem(void) if (_vehicle->supportsMissionItemInt()) { mavlink_mission_request_int_t missionRequest; + memset(&missionRequest, 0, sizeof(missionRequest)); missionRequest.target_system = _vehicle->id(); missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER; missionRequest.seq = _itemIndicesToRead[0]; @@ -372,6 +379,7 @@ void MissionManager::_requestNextMissionItem(void) } else { mavlink_mission_request_t missionRequest; + memset(&missionRequest, 0, sizeof(missionRequest)); missionRequest.target_system = _vehicle->id(); missionRequest.target_component = MAV_COMP_ID_MISSIONPLANNER; missionRequest.seq = _itemIndicesToRead[0]; @@ -523,7 +531,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo if (missionItemInt) { mavlink_mission_item_int_t missionItem; - + memset(&missionItem, 0, sizeof(missionItem)); missionItem.target_system = _vehicle->id(); missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER; missionItem.seq = missionRequest.seq; @@ -547,6 +555,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo } else { mavlink_mission_item_t missionItem; + memset(&missionItem, 0, sizeof(missionItem)); missionItem.target_system = _vehicle->id(); missionItem.target_component = MAV_COMP_ID_MISSIONPLANNER; missionItem.seq = missionRequest.seq; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f0daf4379766ef36af3ee4acd436efbcba530f05..71537edeaa5cd61e099590e3af88d5a6da9f1006 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1523,6 +1523,8 @@ void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool send mavlink_message_t msg; mavlink_request_data_stream_t dataStream; + memset(&dataStream, 0, sizeof(dataStream)); + dataStream.req_stream_id = stream; dataStream.req_message_rate = rate; dataStream.start_stop = 1; // start @@ -2079,6 +2081,7 @@ void Vehicle::_sendMavCommandAgain(void) mavlink_message_t msg; mavlink_command_long_t cmd; + memset(&cmd, 0, sizeof(cmd)); cmd.command = queuedCommand.command; cmd.confirmation = 0; cmd.param1 = queuedCommand.rgParam[0]; @@ -2304,6 +2307,7 @@ void Vehicle::_ackMavlinkLogData(uint16_t sequence) { mavlink_message_t msg; mavlink_logging_ack_t ack; + memset(&ack, 0, sizeof(ack)); ack.sequence = sequence; ack.target_component = _defaultComponentId; ack.target_system = id(); diff --git a/src/comm/MockLinkMissionItemHandler.cc b/src/comm/MockLinkMissionItemHandler.cc index 5764888dff4b8b95338fdfe0fedeb909911bd403..5fa572db1bac1dd46d27347865693cf8018da147 100644 --- a/src/comm/MockLinkMissionItemHandler.cc +++ b/src/comm/MockLinkMissionItemHandler.cc @@ -240,6 +240,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber) mavlink_message_t message; mavlink_mission_request_t missionRequest; + memset(&missionRequest, 0, sizeof(missionRequest)); missionRequest.target_system = _mavlinkProtocol->getSystemId(); missionRequest.target_component = _mavlinkProtocol->getComponentId(); missionRequest.seq = sequenceNumber; @@ -264,6 +265,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType) mavlink_message_t message; mavlink_mission_ack_t missionAck; + memset(&missionAck, 0, sizeof(missionAck)); missionAck.target_system = _mavlinkProtocol->getSystemId(); missionAck.target_component = _mavlinkProtocol->getComponentId(); missionAck.type = ackType;