任何情况下防止yaw给到0,解决碰撞检测发生后,飞机悬停在天上,按悬停控制一下后飞机自旋降落,最后3米失控掉地的bug(不知是否解决)

This commit is contained in:
pxzleo 2017-04-09 10:49:06 +08:00
parent 2d4217d2f8
commit 24db6c7dde

View File

@ -749,13 +749,18 @@ namespace Plane.Copters
public async Task SetChannelsAsync(ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null, ushort? ch5 = null, ushort? ch6 = null, ushort? ch7 = null, ushort? ch8 = null)
{
//某些情况下ch4设置成0会导致自旋
ushort checkyaw = ch4 ?? ch4in;
if ((checkyaw < 1200)|| (checkyaw > 1800))
checkyaw = 1500;
////
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = compid;
rc.target_system = sysid;
rc.chan1_raw = ch1 ?? ch1in;
rc.chan2_raw = ch2 ?? ch2in;
rc.chan3_raw = ch3 ?? ch3in;
rc.chan4_raw = ch4 ?? ch4in;
rc.chan4_raw = checkyaw;
rc.chan5_raw = ch5 ?? ch5in;
rc.chan6_raw = ch6 ?? ch6in;
rc.chan7_raw = ch7 ?? ch7in;
@ -765,20 +770,47 @@ namespace Plane.Copters
public async Task SetMobileControlAsync(ushort? ch1 = null, ushort? ch2 = null, ushort? ch3 = null, ushort? ch4 = null, ushort? ch5 = null, ushort? ch6 = null, ushort? ch7 = null, ushort? ch8 = null, float? yaw = null, float? alt = null)
{
MAVLink.mavlink_rc_mobile_control_t rc = new MAVLink.mavlink_rc_mobile_control_t();
/* MAVLink.mavlink_rc_mobile_control_t rc = new MAVLink.mavlink_rc_mobile_control_t();
rc.target_component = compid;
rc.target_system = sysid;
rc.chan1_raw = ch1 ?? ch1in;
rc.chan2_raw = ch2 ?? ch2in;
rc.chan3_raw = ch3 ?? ch3in;
rc.chan4_raw = ch4 ?? ch4in;
rc.chan5_raw = ch5 ?? ch5in;
rc.chan6_raw = ch6 ?? ch6in;
rc.chan7_raw = ch7 ?? ch7in;
rc.chan8_raw = ch8 ?? ch8in;
rc.Yaw = yaw ?? this.yaw;
rc.alt = alt ?? this.alt;
await SendPacketAsync(rc);
*/
float ch4yaw;
ch4yaw = yaw ?? this.yaw;
if (ch4yaw != this.yaw)
{
ch4yaw = ch4yaw % 360;
await DoCommandAsync(MAVLink.MAV_CMD.CONDITION_YAW, ch4yaw, 0, 1, 0, 0, 0, 0);
}
/*
float ch4yaw;
MAVLink.mavlink_rc_channels_override_t rc = new MAVLink.mavlink_rc_channels_override_t();
rc.target_component = compid;
rc.target_system = sysid;
rc.chan1_raw = ch1 ?? ch1in;
rc.chan2_raw = ch2 ?? ch2in;
rc.chan3_raw = ch3 ?? ch3in;
rc.chan4_raw = ch4 ?? ch4in;
rc.chan4_raw = 1500;
rc.chan5_raw = ch5 ?? ch5in;
rc.chan6_raw = ch6 ?? ch6in;
rc.chan7_raw = ch7 ?? ch7in;
rc.chan8_raw = ch8 ?? ch8in;
rc.Yaw = yaw ?? this.yaw;
rc.alt = alt ?? this.alt;
ch4yaw= yaw ?? this.yaw;
rc.chan4_raw =(ushort)ch4yaw;
await SendPacketAsync(rc);
*/
}
public async Task<float> GetParamAsync(string paramName, int millisecondsTimeout = Timeout.Infinite)