2D模拟简单灯光

3D模拟移动和简单灯光和观测点
添加校准指南针
修改摆放角度
修改模拟飞行中起飞的方案
通信模块:多条mavlink指令采用一起发送的方式
This commit is contained in:
zxd 2018-12-21 11:31:13 +08:00
parent cb64fd625a
commit 6aa6f793e9
6 changed files with 78 additions and 28 deletions

View File

@ -182,5 +182,10 @@ namespace Plane.Copters
/// 飞机上通信模块版本
/// </summary>
byte CommModuleVersion { get; }
/// <summary>
/// LED颜色
/// </summary>
string LEDColor { get; set; }
}
}

View File

@ -33,7 +33,6 @@ namespace Plane.CommunicationManagement
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
private byte[] SetChannels(ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null, ushort? ch5 = null, ushort? ch6 = null, ushort? ch7 = null, ushort? ch8 = null)
{
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
@ -139,6 +138,7 @@ namespace Plane.CommunicationManagement
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.MISSION_START, hour_utc, minute_utc, second_utc, 0, 0 , 2, 0);
await WriteCommPacketAsync(0, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
}
/// <summary>
/// 解锁
/// </summary>
@ -150,17 +150,14 @@ namespace Plane.CommunicationManagement
byte[] batchPacket = null;
GetCopterIds(copters,out copterId, out batchPacket);
await SetChannelsAsync(copters, 1500, 1500, 1100, 1500);
byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
byte[] packet2 = SetModeAsync(FlightMode.ALT_HOLD);
byte[] packet3 = DoARMAsync(true);
byte[] packet;
packet = SetModeAsync(FlightMode.ALT_HOLD);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
await Task.Delay(100).ConfigureAwait(false);
packet = DoARMAsync(true);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
/// <summary>
@ -213,16 +210,14 @@ namespace Plane.CommunicationManagement
byte[] batchPacket = null;
GetCopterIds(copters, out copterId, out batchPacket);
byte[] packet;
packet = SetModeAsync(FlightMode.GUIDED);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
byte[] packet1 = SetModeAsync(FlightMode.GUIDED);
await Task.Delay(10).ConfigureAwait(false);
await SetChannelsAsync(copters, 1500, 1500, 1500, 1500);
await Task.Delay(10).ConfigureAwait(false);
byte[] packet2 = SetChannels(1500, 1500, 1500, 1500);
packet = DoCommandAsync(MAVLink.MAV_CMD.TAKEOFF, 0, 0, 0, 0, 0, 0, alt);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
byte[] packet3 = DoCommandAsync(MAVLink.MAV_CMD.TAKEOFF, 0, 0, 0, 0, 0, 0, alt);
byte[] data = packet1.Concat(packet2).Concat(packet3).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
/// <summary>
@ -281,8 +276,12 @@ namespace Plane.CommunicationManagement
byte[] batchPacket = null;
GetCopterIds(copters, out copterId, out batchPacket);
byte[] packet = DoARMAsync(false);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
byte[] packet1 = SetChannels(1500, 1500, 1100, 1500);
byte[] packet2 = DoARMAsync(false);
byte[] data = packet1.Concat(packet2).ToArray();
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
/// <summary>
@ -290,14 +289,20 @@ namespace Plane.CommunicationManagement
/// </summary>
/// <param name="motor"></param>
/// <returns></returns>
public async Task MotorTestAsync(int motor, IEnumerable<ICopter> copters = null)
public async Task MotorTestAsync(IEnumerable<ICopter> copters = null)
{
short copterId = 0;
byte[] batchPacket = null;
GetCopterIds(copters, out copterId, out batchPacket);
byte[] packet = DoMotorTestAsync(motor, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket);
//1-4代表1-4电机
byte[] data1 = DoMotorTestAsync(1, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
byte[] data2 = DoMotorTestAsync(2, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
byte[] data3 = DoMotorTestAsync(3, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
byte[] data4 = DoMotorTestAsync(4, MAVLink.MOTOR_TEST_THROTTLE_TYPE.MOTOR_TEST_THROTTLE_PERCENT, 5, 5);
byte[] data = data1.Concat(data2).Concat(data3).Concat(data4).ToArray();
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket);
}
/// <summary>
@ -310,10 +315,12 @@ namespace Plane.CommunicationManagement
byte[] batchPacket = null;
GetCopterIds(copters, out copterId, out batchPacket);
await SetChannelsAsync(copters, 1500, 1500, 1500, 1500);
byte[] packet1 = SetChannels(1500, 1500, 1500, 1500);
byte[] packet = SetModeAsync(FlightMode.LOITER);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
byte[] packet2 = SetModeAsync(FlightMode.LOITER);
byte[] data = packet1.Concat(packet2).ToArray();
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, data, batchPacket).ConfigureAwait(false);
}
/// <summary>
@ -328,7 +335,26 @@ namespace Plane.CommunicationManagement
GetCopterIds(copters, out copterId, out batchPacket);
byte[] packet = SetModeAsync(FlightMode.ALT_HOLD);
await WriteCommPacketAsync((short)copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet, batchPacket).ConfigureAwait(false);
}
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);
}
public async Task DoCancelCalibrationCompassAsync(short copterId)
{
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_CANCEL_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
}
public async Task DoAcceptCalibrationCompassAsync(short copterId)
{
byte[] packet = DoCommandAsync(MAVLink.MAV_CMD.DO_ACCEPT_MAG_CAL, 0, 0, 1, 0, 0, 0, 0);
await WriteCommPacketAsync(copterId, MavComm.COMM_DOWNLOAD_COMM, packet).ConfigureAwait(false);
}
private byte[] SetModeAsync(FlightMode mode)
@ -473,6 +499,8 @@ namespace Plane.CommunicationManagement
}
}
public byte[] GenerateRTKPacketAsync<TMavlinkPacket>(byte messageType, TMavlinkPacket indata, int rtklength)
{
byte[] data;

View File

@ -669,6 +669,13 @@ namespace Plane.Copters
protected set { Set(nameof(CommModuleVersion), ref _CommModuleVersion, value); }
}
private string _LEDColor;
public string LEDColor
{
get { return _LEDColor; }
set { Set(nameof(LEDColor), ref _LEDColor, value); }
}
#if PRIVATE
public
#else

View File

@ -31,6 +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;

View File

@ -441,6 +441,7 @@ namespace Plane.Copters
{
AirSpeed = (float)airSpeed;
}
//Windows.Messages.Message.Show(AirSpeed.ToString());
GroundSpeed = AirSpeed;
_lastCalcSpeedPoint = new PLLocation(this);
_lastCalcSpeedTime = DateTime.Now;

View File

@ -17,7 +17,9 @@ namespace Plane.Protocols
public const int MAVLINK_LITTLE_ENDIAN = 1;
public const int MAVLINK_BIG_ENDIAN = 0;
public const byte MAVLINK_STX = 254;
//飞控4.0以后 254 - 240
//public const byte MAVLINK_STX = 254;
public const byte MAVLINK_STX = 240;
public const byte MAVLINK_ENDIAN = MAVLINK_LITTLE_ENDIAN;
@ -170,6 +172,12 @@ namespace Plane.Protocols
START_RX_PAIR = 500,
///<summary> | </summary>
ENUM_END = 501,
///<summary> 校准指南针| </summary>
DO_START_MAG_CAL = 42424,
///<summary> 放弃指南针校准| </summary>
DO_CANCEL_MAG_CAL = 42425,
///<summary> 接受指南针校准|</summary>
DO_ACCEPT_MAG_CAL = 42426,
};
/** @brief */