iNavFlight / inav

INAV: Navigation-enabled flight control software
https://inavflight.github.io
GNU General Public License v3.0
3.18k stars 1.48k forks source link

SBUS Servo output causes weird behavior during Failsafe #6027

Closed danarrib closed 4 years ago

danarrib commented 4 years ago

Current Behavior

Since INAV 2.5, Servos will full deflect (2000uS value) when a RX failsafe condition is met. It occurs with aircraft disarmed. I didn't test is in flight.

https://www.youtube.com/watch?v=ykKG9P0cx4U

Steps to Reproduce

  1. Power up the airplane
  2. Power up the radio transmitter
  3. Test if servos are working fine
  4. Power off the radio transmitter to force a Failsafe state. Servos will full deflect immediately.

Expected behavior

Like on previous versions, servos would just rest on neutral position (usually 1500uS).

Suggested solution(s)

Review the commit https://github.com/iNavFlight/inav/commit/041f2c98515416d43bfb803c24550ae19a8d7d49 since it's what it's causing this behavior. This is the commit that added SBUS Servo output capability to INAV.

I custom built a HEX file without this commit, and the servos behavior during Failsafe are like before.

Additional context

I'm not sure if this is a problem by itself. I didn't flew it and I don't know if this happens with aircraft armed, GPS fix and everything good for a FS RTH. So it needs additional testing. I'm opening this issue more to let the dev team know that this strange behavior exists.

I'm using a FrSky R9MM Receiver, SBUS protocol. On OpenTX, Failsafe is set to "No Pulses". Servos are Turnigy 9g Analog.

This is a bare minimal diff to reproduce the problem:

defaults noreboot
mmix reset
mmix 0  1.000  0.000  0.000  0.000
mmix 1  1.000  0.000  0.000  0.000

smix reset
smix 0 3 0 80 0 -1
smix 1 3 1 80 0 -1
smix 2 4 0 -80 0 -1
smix 3 4 1 80 0 -1

servo 3 1000 2000 1500 -125
servo 4 1000 2000 1500 125

feature MOTOR_STOP
feature PWM_OUTPUT_ENABLE

serial 2 32 115200 115200 0 115200

set mag_hardware = NONE
set pitot_hardware = NONE
set platform_type = AIRPLANE
set model_preview_type = 8
set small_angle = 180
set applied_defaults = 3

save
issue-label-bot[bot] commented 4 years ago

Issue-Label Bot is automatically applying the label BUG to this issue, with a confidence of 0.97. Please mark this comment with :thumbsup: or :thumbsdown: to give our bot feedback!

Links: app homepage, dashboard and code for this bot.

digitalentity commented 4 years ago

Can't reproduce on latest master using MATEKF722-STD board and X8R receiver set to No-Pulses.

My minimal config:

defaults noreboot

mmix reset
mmix 0  1.000  0.000  0.000  0.000
mmix 1  1.000  0.000  0.000  0.000

smix reset
smix 0 3 0 80 0 -1
smix 1 3 1 80 0 -1
smix 2 4 0 -80 0 -1
smix 3 4 1 80 0 -1

servo 3 1000 2000 1500 -125
servo 4 1000 2000 1500 125

feature MOTOR_STOP
feature PWM_OUTPUT_ENABLE

map TAER

serial 2 32 115200 115200 0 115200

set acc_hardware = MPU6500
set mag_hardware = NONE
set baro_hardware = BMP280
set pitot_hardware = NONE
set platform_type = AIRPLANE
set model_preview_type = 8
set small_angle = 180
set applied_defaults = 3

save

I did notice a difference in behavior between 2.4.0 and master - on 2.4.0 on failsafe on my setup RC channels drop to 880, while on master they all drop to 988.

This was indeed introduced by 041f2c9 - fix underway.

digitalentity commented 4 years ago

It appears that R9MM receiver is setting channel values to zero (880ms) before setting the RX_FRAME_FAILSAFE flag. Commit 041f2c9 added clipping of the min value to 988ms which is within normal range and thus was propagated to servos before FS was detected.

My X8R doesn't exhibit this behavior and sets the RX_FRAME_FAILSAFE flag correctly so channels don't affect the behavior of the aircraft regardless of their value.

digitalentity commented 4 years ago

@danarrib please let me know if #6088 fixes the issue. This bug looks serious since it may cause a disarm in flight. If the issue is fixed we should look into a patch release 2.5.3.

danarrib commented 4 years ago

Ok, I tested your fix on my airplane and it worked fine. Now the servos behavior during Failsafe are the same as on INAV 2.4. Servos keep the current values once a FS is detected.

Thanks @digitalentity !