添加版本控制 version=255为完整版本
修改起飞方案模拟实际航点的起飞模式 添加校准指南针和加速计
This commit is contained in:
parent
6aa6f793e9
commit
35b8a5282e
@ -198,6 +198,23 @@ namespace Plane.CommunicationManagement
|
||||
return packetNum;
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// 读取参数
|
||||
/// </summary>
|
||||
/// <param name="paramname"></param>
|
||||
/// <param name="copters"></param>
|
||||
/// <returns></returns>
|
||||
public async Task ReadParamAsnyc(string paramname, IEnumerable<ICopter> copters = null)
|
||||
{
|
||||
short copterId = 0;
|
||||
byte[] batchPacket = null;
|
||||
GetCopterIds(copters, out copterId, out batchPacket);
|
||||
|
||||
byte[] packet = GetParam2Async(paramname);
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 起飞测试
|
||||
/// </summary>
|
||||
@ -235,6 +252,9 @@ namespace Plane.CommunicationManagement
|
||||
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// 获取版本
|
||||
/// </summary>
|
||||
@ -338,13 +358,48 @@ namespace Plane.CommunicationManagement
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 校准加速计
|
||||
/// </summary>
|
||||
/// <param name="copterId"></param>
|
||||
/// <returns></returns>
|
||||
public async Task DoStartPreflightCompassAsync(short copterId)
|
||||
{
|
||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 1, 0, 0);
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 校准加速计下一步
|
||||
/// </summary>
|
||||
/// <param name="copterId"></param>
|
||||
/// <returns></returns>
|
||||
public async Task DoNextPreflightCompassAsync(short copterId)
|
||||
{
|
||||
MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
|
||||
req.command = 1;
|
||||
req.result = 1;
|
||||
|
||||
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 校准指南针
|
||||
/// </summary>
|
||||
/// <param name="copterId"></param>
|
||||
/// <returns></returns>
|
||||
public async Task DoCalibrationCompassAsync(short copterId)
|
||||
{
|
||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 1, 1, 0, 0, 0, 0);
|
||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 放弃校准指南针
|
||||
/// </summary>
|
||||
/// <param name="copterId"></param>
|
||||
/// <returns></returns>
|
||||
public async Task DoCancelCalibrationCompassAsync(short copterId)
|
||||
{
|
||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_CANCEL_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
|
||||
@ -557,6 +612,22 @@ namespace Plane.CommunicationManagement
|
||||
return GeneratePacket((byte)MAVLink.MAVLINK_MSG_ID_PARAM_SET, req);
|
||||
}
|
||||
|
||||
private byte[] GetParam2Async(string paramname)
|
||||
{
|
||||
var paramId = Encoding.ASCII.GetBytes(paramname);
|
||||
Array.Resize(ref paramId, 16);
|
||||
|
||||
var req = new MAVLink.mavlink_param_request_read_t
|
||||
{
|
||||
param_index = -1,
|
||||
target_system = 1,
|
||||
target_component = 1,
|
||||
param_id = paramId
|
||||
};
|
||||
|
||||
return GeneratePacket(MAVLink.MAVLINK_MSG_ID_PARAM_REQUEST_READ, req);
|
||||
}
|
||||
|
||||
private byte[] DoLEDCommandAsync()
|
||||
{
|
||||
MAVLink.mavlink_msg_id_led_control led = new MAVLink.mavlink_msg_id_led_control();
|
||||
|
@ -614,10 +614,20 @@ namespace Plane.Copters
|
||||
protected set { Set(nameof(SatCount), ref _SatCount, value); }
|
||||
}
|
||||
|
||||
public float RetainInt
|
||||
{
|
||||
get { return BitConverter.ToSingle(Retain,0); }
|
||||
}
|
||||
|
||||
|
||||
public byte[] Retain
|
||||
{
|
||||
get { return _Retain; }
|
||||
protected set { Set(nameof(Retain), ref _Retain, value); }
|
||||
protected set
|
||||
{
|
||||
Set(nameof(Retain), ref _Retain, value);
|
||||
RaisePropertyChanged(nameof(RetainInt));
|
||||
}
|
||||
}
|
||||
|
||||
public CopterState State
|
||||
|
@ -31,7 +31,7 @@ namespace Plane.Copters
|
||||
GpsHdop = _internalCopter.gpshdop;
|
||||
Altitude = _internalCopter.gpsalt;
|
||||
Retain = BitConverter.GetBytes(_internalCopter.retain);
|
||||
Windows.Messages.Message.Show("_internalCopter.retain = " + _internalCopter.retain.ToString());
|
||||
|
||||
Voltage = _internalCopter.battery_voltage;
|
||||
CommModuleMode = (FlightMode)_internalCopter.commModuleMode;
|
||||
CommModuleVersion = _internalCopter.commModuleVersion;
|
||||
|
@ -58,7 +58,7 @@ namespace Plane.Copters
|
||||
public byte gpsstatus { get; set; }
|
||||
public float gpshdop { get; set; }
|
||||
public byte satcount { get; set; }
|
||||
public int retain { get; set; }
|
||||
public float retain { get; set; }
|
||||
public float groundspeed { get; set; }
|
||||
public float groundcourse { get; set; }
|
||||
public double lat { get; set; }
|
||||
|
@ -144,7 +144,7 @@ namespace Plane.Protocols
|
||||
public Int32 control_mode;
|
||||
public UInt32 lat;
|
||||
public UInt32 lng;
|
||||
public Int32 retain;
|
||||
public float retain;
|
||||
public Int32 alt;
|
||||
|
||||
public Int16 gps_status;
|
||||
|
Loading…
Reference in New Issue
Block a user