飞机LED灯光修改
GPS不精准时,显示飞机位置(用于室内写航点)
This commit is contained in:
parent
471f0ba872
commit
c7e5212746
@ -33,6 +33,11 @@
|
||||
/// <summary>
|
||||
/// 命令飞行器起飞。
|
||||
/// </summary>
|
||||
TakeOff = 22
|
||||
TakeOff = 22,
|
||||
|
||||
/// <summary>
|
||||
/// 命令LED颜色改变
|
||||
/// </summary>
|
||||
LEDControl = 203
|
||||
}
|
||||
}
|
||||
|
@ -49,5 +49,20 @@
|
||||
/// 获取或设置序号。
|
||||
/// </summary>
|
||||
ushort Sequence { get; set; }
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 获取或设置LED控制RGB的Red
|
||||
/// </summary>
|
||||
float R { get; set; }
|
||||
|
||||
/// <summary>
|
||||
/// 获取或设置LED控制RGB的Green
|
||||
/// </summary>
|
||||
float G { get; set; }
|
||||
|
||||
/// <summary>
|
||||
/// 获取或设置LED控制RGB的Blue
|
||||
/// </summary>
|
||||
float B { get; set; }
|
||||
}
|
||||
}
|
||||
|
@ -157,6 +157,11 @@ namespace Plane.Copters
|
||||
|
||||
private float _Yaw;
|
||||
|
||||
//初始时位置:使用地图Center
|
||||
private double _RecordLat;
|
||||
|
||||
private double _RecordLng;
|
||||
|
||||
#endregion Backing Fields
|
||||
|
||||
public CopterImplSharedPart(SynchronizationContext uiSyncContext) : base(uiSyncContext)
|
||||
@ -560,6 +565,18 @@ namespace Plane.Copters
|
||||
protected set { Set(nameof(Longitude), ref _Longitude, value); }
|
||||
}
|
||||
|
||||
public double RecordLat
|
||||
{
|
||||
get { return _RecordLat; }
|
||||
set { Set(nameof(RecordLat), ref _RecordLat, value); }
|
||||
}
|
||||
|
||||
public double RecordLng
|
||||
{
|
||||
get { return _RecordLng; }
|
||||
set { Set(nameof(RecordLng), ref _RecordLng, value); }
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// 获取任务总数。
|
||||
/// </summary>
|
||||
|
@ -26,8 +26,6 @@ namespace Plane.Copters
|
||||
{
|
||||
case MAVLINK_MSG_ID_GPS_RAW_INT: //需要
|
||||
{
|
||||
Latitude = _internalCopter.lat;
|
||||
Longitude = _internalCopter.lng;
|
||||
SatCount = _internalCopter.satcount;
|
||||
GpsFixType = _internalCopter.gpsstatus.ToGpsFixType();
|
||||
GpsHdop = _internalCopter.gpshdop;
|
||||
@ -35,9 +33,14 @@ namespace Plane.Copters
|
||||
|
||||
if (IsGpsAccurate)
|
||||
{
|
||||
RecordLat = _internalCopter.lat;
|
||||
RecordLng = _internalCopter.lng;
|
||||
}
|
||||
|
||||
Latitude = RecordLat;
|
||||
Longitude = RecordLng;
|
||||
UpdateFlightDataIfNeeded();
|
||||
RaiseLocationChangedIfNeeded();
|
||||
}
|
||||
|
||||
RaiseDataStreamReceived(PDataStreamType.GPS_RAW_INT);
|
||||
|
||||
|
@ -240,9 +240,19 @@ namespace Plane.Copters
|
||||
req.autocontinue = 1;
|
||||
|
||||
req.frame = (byte)frame;
|
||||
if (mission.Command == FlightCommand.LEDControl)
|
||||
{
|
||||
req.x = mission.R;
|
||||
req.y = mission.G;
|
||||
req.z = mission.B;
|
||||
}
|
||||
else
|
||||
{
|
||||
req.x = (float)mission.Latitude;
|
||||
req.y = (float)mission.Longitude;
|
||||
req.z = mission.Altitude;
|
||||
}
|
||||
|
||||
|
||||
req.param1 = mission.Param1;
|
||||
req.param2 = mission.Param2;
|
||||
|
@ -19,6 +19,9 @@ namespace Plane.Copters
|
||||
private float _Param3;
|
||||
private float _Param4;
|
||||
private ushort _Sequence;
|
||||
private float _R;
|
||||
private float _G;
|
||||
private float _B;
|
||||
|
||||
#endregion Backing Fields
|
||||
|
||||
@ -107,6 +110,26 @@ namespace Plane.Copters
|
||||
set { Set(nameof(Sequence), ref _Sequence, value); }
|
||||
}
|
||||
|
||||
public float R
|
||||
{
|
||||
get { return _R; }
|
||||
set { Set(nameof(R), ref _R, value); }
|
||||
}
|
||||
|
||||
public float G
|
||||
{
|
||||
get { return _G; }
|
||||
set { Set(nameof(G), ref _G, value); }
|
||||
}
|
||||
|
||||
public float B
|
||||
{
|
||||
get { return _B; }
|
||||
set { Set(nameof(B), ref _B, value); }
|
||||
}
|
||||
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// 创建降落任务。
|
||||
/// </summary>
|
||||
@ -160,7 +183,16 @@ namespace Plane.Copters
|
||||
Altitude = alt
|
||||
};
|
||||
|
||||
|
||||
|
||||
public static IMission CreateLEDControlMission(int delay, int ledmode, int ledrate, int ledtimes, byte red, byte green, byte blue) => new Mission
|
||||
{
|
||||
Command = FlightCommand.LEDControl,
|
||||
Param1 = delay, //灯光延时 单位:100ms
|
||||
Param2 = ledmode, //灯光模式 0.常亮 1.闪烁 2.随机闪烁(RGB无意义)
|
||||
Param3 = ledrate, //闪烁延时 单位:100ms
|
||||
Param4 = ledtimes, //次数 (暂无意义)
|
||||
R = red, //Red
|
||||
G = green, //Green
|
||||
B = blue //Blue
|
||||
};
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user