Browse Source

MissionItem memset to 8 instead of 0

QGC4.4
Pierre TILAK 6 years ago
parent
commit
bf88ab15c5
  1. 2
      src/MissionManager/MissionManager.cc

2
src/MissionManager/MissionManager.cc

@ -46,7 +46,7 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC
mavlink_message_t messageOut; mavlink_message_t messageOut;
mavlink_mission_item_t missionItem; mavlink_mission_item_t missionItem;
memset(&missionItem, 8, sizeof(missionItem)); memset(&missionItem, 0, sizeof(missionItem));
missionItem.target_system = _vehicle->id(); missionItem.target_system = _vehicle->id();
missionItem.target_component = _vehicle->defaultComponentId(); missionItem.target_component = _vehicle->defaultComponentId();
missionItem.seq = 0; missionItem.seq = 0;

Loading…
Cancel
Save