修改支持多台飞机校准通讯接口类
This commit is contained in:
parent
35b8a5282e
commit
4ae451aded
@ -363,10 +363,14 @@ namespace Plane.CommunicationManagement
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="copterId"></param>
|
/// <param name="copterId"></param>
|
||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoStartPreflightCompassAsync(short copterId)
|
public async Task DoStartPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.PREFLIGHT_CALIBRATION, 0, 0, 0, 0, 1, 0, 0);
|
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);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -374,14 +378,18 @@ namespace Plane.CommunicationManagement
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="copterId"></param>
|
/// <param name="copterId"></param>
|
||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoNextPreflightCompassAsync(short copterId)
|
public async Task DoNextPreflightCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
|
MAVLink.mavlink_command_ack_t req = new MAVLink.mavlink_command_ack_t();
|
||||||
req.command = 1;
|
req.command = 1;
|
||||||
req.result = 1;
|
req.result = 1;
|
||||||
|
|
||||||
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
|
byte[] packet = GeneratePacket(MAVLink.MAVLINK_MSG_ID_COMMAND_ACK, req);
|
||||||
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -389,10 +397,14 @@ namespace Plane.CommunicationManagement
|
|||||||
/// </summary>
|
/// </summary>
|
||||||
/// <param name="copterId"></param>
|
/// <param name="copterId"></param>
|
||||||
/// <returns></returns>
|
/// <returns></returns>
|
||||||
public async Task DoCalibrationCompassAsync(short copterId)
|
public async Task DoCalibrationCompassAsync(IEnumerable<ICopter> copters = null)
|
||||||
{
|
{
|
||||||
|
short copterId = 0;
|
||||||
|
byte[] batchPacket = null;
|
||||||
|
GetCopterIds(copters, out copterId, out batchPacket);
|
||||||
|
|
||||||
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_START_MAG_CAL, 0, 1, 1, 0, 0, 0, 0);
|
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);
|
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
|
Loading…
Reference in New Issue
Block a user