62 lines
2.2 KiB
C#
62 lines
2.2 KiB
C#
|
using Plane.Protocols;
|
|||
|
using System.Collections.Generic;
|
|||
|
using static Plane.Protocols.MAVLink;
|
|||
|
|
|||
|
namespace Plane.Copters
|
|||
|
{
|
|||
|
public partial class PLCopter
|
|||
|
{
|
|||
|
private void AnalyzeMissionAckPacket(byte[] buffer)
|
|||
|
{
|
|||
|
var packet = buffer.ByteArrayToStructure<mavlink_mission_ack_t>(6);
|
|||
|
_writeMissionListResult = (MAV_MISSION_RESULT)packet.type;
|
|||
|
}
|
|||
|
|
|||
|
private void AnalyzeMissionCountPacket(byte[] buffer)
|
|||
|
{
|
|||
|
var packet = buffer.ByteArrayToStructure<mavlink_mission_count_t>(6);
|
|||
|
MissionCount = packet.count;
|
|||
|
}
|
|||
|
|
|||
|
private void AnalyzeMissionItemPacket(byte[] buffer)
|
|||
|
{
|
|||
|
var packet = buffer.ByteArrayToStructure<mavlink_mission_item_t>(6);
|
|||
|
var mission = new Mission
|
|||
|
{
|
|||
|
Altitude = packet.z,
|
|||
|
Command = (FlightCommand)packet.command,
|
|||
|
Latitude = packet.x,
|
|||
|
Longitude = packet.y,
|
|||
|
Param1 = packet.param1,
|
|||
|
Param2 = packet.param2,
|
|||
|
Param3 = packet.param3,
|
|||
|
Param4 = packet.param4,
|
|||
|
Sequence = packet.seq
|
|||
|
};
|
|||
|
if (_missionList == null)
|
|||
|
{
|
|||
|
if (mission.Sequence == 0)
|
|||
|
{
|
|||
|
_missionList = new List<IMission> { mission };
|
|||
|
}
|
|||
|
}
|
|||
|
else if (_missionList.Count > mission.Sequence) _missionList[mission.Sequence] = mission;
|
|||
|
else if (_missionList.Count == mission.Sequence) _missionList.Add(mission);
|
|||
|
RaiseMissionItemReceived(new MissionItemReceivedEventArgs(mission));
|
|||
|
}
|
|||
|
|
|||
|
private void AnalyzeMissionRequestPacket(byte[] buffer)
|
|||
|
{
|
|||
|
var packet = buffer.ByteArrayToStructure<mavlink_mission_request_t>(6);
|
|||
|
_copterRequestingMissionSeq = packet.seq;
|
|||
|
}
|
|||
|
|
|||
|
private void AnalyzeSetPairPacket(byte[] buffer)
|
|||
|
{
|
|||
|
IsPairing = false;
|
|||
|
var packet = buffer.ByteArrayToStructure<mavlink_set_pair_t>(6);
|
|||
|
RaisePairingCompleted(new PairingCompletedEventArgs(packet.pair == 1, packet.RxID, packet.TxID));
|
|||
|
}
|
|||
|
}
|
|||
|
}
|