iNavFlight / inav

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

Brief throttle cutoff during Mission on multicopter #1309

Closed giacomo892 closed 6 years ago

giacomo892 commented 7 years ago

I'm running INAV 1.5.1 NAZE on F450 Multicopter with the configuration below.

I was alerted by a youtube user (iforce2d) that uploaded this video to his channel:

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

He noticed short engines cutoffs and after he crashed his exacopter with major damages.

I went flying today and I noticed the same behaviour. I configured a mission with 3 waypoints

1st)60m high

2nd)100m high

3th)60m as far I can remember

As the quad reached the 2nd waypoint before rotating to come back to point 3 the engines stopped running briefly (or is it just an impression?) and then the navigation went right until I landed without noticing any issues also in other flights made without resetting the FC:

https://www.youtube.com/watch?v=B_evwmzU4EI (my footage, you can hear motor cut on turning)

As far I can tell after the reaching of wp2 the mission plan was to lower the altitude so am I not really sure if this problem is related to not correctly setted hovering throttle (maybe should I set it a bit more than 1500?) but... the mission was already holding altitude at that point so this seems really strange ,usally drops happens when enabling altitude holding not when it is enabled.

When I landed I checked there were no I2C errors. At that time I had 18 sats in view.

version

INAV/NAZE 1.5.1 Jan 5 2017 / 11:29:36 (556168d)

pflags

Persistent config flags: 0x00000000

dump master

mixer

mixer QUADX mmix reset smix reset

feature

feature -RX_PPM feature -VBAT feature -UNUSED_1 feature -RX_SERIAL feature -MOTOR_STOP feature -SERVO_TILT feature -SOFTSERIAL feature -GPS feature -FAILSAFE feature -SONAR feature -TELEMETRY feature -CURRENT_METER feature -3D feature -RX_PARALLEL_PWM feature -RX_MSP feature -RSSI_ADC feature -LED_STRIP feature -DASHBOARD feature -UNUSED_2 feature -BLACKBOX feature -CHANNEL_FORWARDING feature -TRANSPONDER feature -AIRMODE feature -SUPEREXPO feature -VTX feature -RX_SPI feature -SOFTSPI feature -PWM_SERVO_DRIVER feature -PWM_OUTPUT_ENABLE feature -OSD feature RX_PPM feature VBAT feature GPS feature FAILSAFE feature TELEMETRY feature PWM_OUTPUT_ENABLE

beeper

beeper GYRO_CALIBRATED beeper HW_FAILURE beeper RX_LOST beeper RX_LOST_LANDING beeper DISARMING beeper ARMING beeper ARMING_GPS_FIX beeper BAT_CRIT_LOW beeper BAT_LOW beeper GPS_STATUS beeper RX_SET beeper ACC_CALIBRATION beeper ACC_CALIBRATION_FAIL beeper READY_BEEP beeper MULTI_BEEPS beeper DISARM_REPEAT beeper ARMED beeper SYSTEM_INIT beeper ON_USB beeper LAUNCH_MODE

map

map AETR1234

serial

serial 0 17 57600 38400 57600 115200 serial 1 2 57600 57600 0 115200

set looptime = 2000 set i2c_overclock = OFF set gyro_sync = OFF set gyro_sync_denom = 2 set acc_task_frequency = 500 set attitude_task_frequency = 250 set async_mode = NONE set mid_rc = 1500 set min_check = 1100 set max_check = 1900 set rssi_channel = 0 set rssi_scale = 30 set rssi_ppm_invert = OFF set rc_smoothing = ON set input_filtering_mode = OFF set min_throttle = 1150 set max_throttle = 1850 set min_command = 1000 set 3d_deadband_low = 1406 set 3d_deadband_high = 1514 set 3d_neutral = 1460 set 3d_deadband_throttle = 1000 set motor_pwm_rate = 400 set motor_pwm_protocol = STANDARD set fixed_wing_auto_arm = OFF set disarm_kill_switch = ON set auto_disarm_delay = 5 set small_angle = 25 set reboot_character = 82 set gps_provider = UBLOX set gps_sbas_mode = EGNOS set gps_dyn_model = AIR_1G set gps_auto_config =ud = ON set inav_accz_unarmedcal = ON set inav_use_gps_velned = ON set inav_gps_delayt_mode = AT_LEAST set nav_rth_altitude = 1000 set nav_mc_bank_angle = 35 set nav_mc_h set nav_fw_launch_accel = 1863 set nav_fw_launch_detect_time = 40 set nav_fw_launch_thr = 1700 set navt_max_cell_voltage = 43 set vbat_min_cell_voltage = 33 set vbatboard_yaw = 0 set gyro_lpf = 42HZ set moron_threshold = 32 set imu_dcm_kp = 2500 set imu_dcm_ki = 50 se_kill_switch = OFF set failsafe_throttle_low_delay = 200 set failsafe_procedure = RTHzero_y = 16 set acczero_z = -12 set accgain_x = 4071 set accgain_y = 4082 set accgain_z = 4012

rxfux 8 0 0 900 900

aux 9 0 0 900 900 aux 10 0 0 900 900 aux 11 0 0 900 900 aux 12 0 0 0 900 900 0 0 adjrange 7 0 0 900 900 0 0 adjrange 8 0 0 900 900 0 0 adjrange 9 0 0 900 900 0 0 adjrang 0 set nav_vel_p = 100 set nav_vel_i = 50 set nav_vel_d = 10 eron_throw_inverted = OFF set gimbal_mode = NORMAL set fw_iterm_throw_limit = 165 set mode_range_logic_of_hz = 40 set yaw_lpf_hz = 30 set yaw_p_limit = 300 set iterm_ignore_threshold = 200

ACC:MPU6050 BARO:BMP280 MAG:HMC5883 GPS:UBLOX N8M

oleost commented 7 years ago

Do you have an blackbox log of this?

And have you properly calibrated your ESC?

giacomo892 commented 7 years ago

Sorry, no blackbox. ESC calibrated using the standard procedure. Max throttle in configurator (1850) then connect battery.. beeps.... 1000 and done

digitalentity commented 7 years ago

It's a shame that there was no blackbox recording. My best guess is this:

INAV 1.6 uses different scaling for altitude hold PIDs to make altitude control more responsive. Maybe this is what you experienced - the WP#3 is lower than WP#2 and machine started to descend to reach it. Because of more responsive altitude hold controller it dropped throttle a lot to descend - this is what might have been mixed up to motors stopping completely.

Anyway, I think this is not a bug, but so rapid throttle response must still be fixed or at least be allowed to tuned to have more smoothness.

giacomo892 commented 7 years ago

OK. But note this happened on 1.5.1 not 1.6 . I hope we will learn more on what happened to iforce2d hexa since it is crashed after this cutoffs

digitalentity commented 7 years ago

1.5.1 might exhibits similar behavior. I hope @iforce2d will drop by and share his thoughs.

iforce2d commented 7 years ago

I think my problem had something to do with the follow-me thing, because this hex has been flying ok for a couple of months until I attached that. (https://github.com/iforce2d/inavFollowme)

The arduino talks to the FC via a MSP connection and repeatedly sets WP#255 to change the location, altitude and heading, so it uses GCS_NAV mode. I have used this thing a lot on a slightly smaller quad (S500 with flip32+) without seeing this problem. The hex in the video uses a SPF3 EVO running iNav 1.4.0. At the time of the crash it was not really moving anywhere, because the waypoints given to it would all be the same place and it had already reached that location.

The only other strange thing I have noticed with this hex is that occasionally the GPS_FIX flag is lost, usually for a very brief moment (less than a second). But this does not cause the motors to stop, at least in normal position hold mode. When it happens the hex will swerve around for a moment before recovering the correct position. One time this swerving lasted quite a while (ten seconds or more) until I had to intervene and land manually. Unfortunately to investigate this I removed the blackbox SD card from the FC and forgot to put it back in before the flight when it crashed.

Perhaps if GPS_FIX is lost while in GCS_NAV mode something causes the motors to stop?

I fixed up the hex and it has been flying ok again, without the follow-me thingy attached.

version

INAV/SPRACINGF3EVO 1.4.0 Dec 9 2016 / 14:33:13 (6bf7a91)

pflags

Persistent config flags: 0x00000001

dump master

mixer

mixer HEX6X mmix reset smix reset

feature

feature -RX_PPM feature -VBAT feature -UNUSED_1 feature -RX_SERIAL feature -MOTOR_STOP feature -SERVO_TILT feature -SOFTSERIAL feature -GPS feature -FAILSAFE feature -SONAR feature -TELEMETRY feature -CURRENT_METER feature -3D feature -RX_PARALLEL_PWM feature -RX_MSP feature -RSSI_ADC feature -LED_STRIP feature -DASHBOARD feature -UNUSED_2 feature -BLACKBOX feature -CHANNEL_FORWARDING feature -TRANSPONDER feature -AIRMODE feature -SUPEREXPO feature -VTX feature -RX_SPI feature -SOFTSPI feature -PWM_SERVO_DRIVER feature -PWM_OUTPUT_ENABLE feature VBAT feature RX_SERIAL feature MOTOR_STOP feature GPS feature FAILSAFE feature RSSI_ADC feature BLACKBOX feature PWM_OUTPUT_ENABLE

beeper

beeper GYRO_CALIBRATED beeper RX_LOST beeper RX_LOST_LANDING beeper DISARMING beeper ARMING beeper ARMING_GPS_FIX beeper BAT_CRIT_LOW beeper BAT_LOW beeper GPS_STATUS beeper RX_SET beeper ACC_CALIBRATION beeper ACC_CALIBRATION_FAIL beeper READY_BEEP beeper MULTI_BEEPS beeper DISARM_REPEAT beeper ARMED beeper SYSTEM_INIT beeper ON_USB beeper LAUNCH_MODE

map

map AETR1234

serial

serial 20 1 115200 38400 0 115200 serial 0 1 115200 38400 0 115200 serial 1 64 115200 38400 0 115200 serial 2 2 115200 38400 0 115200

led

led 0 0,0::C:0 led 1 0,0::C:0 led 2 0,0::C:0 led 3 0,0::C:0 led 4 0,0::C:0 led 5 0,0::C:0 led 6 0,0::C:0 led 7 0,0::C:0 led 8 0,0::C:0 led 9 0,0::C:0 led 10 0,0::C:0 led 11 0,0::C:0 led 12 0,0::C:0 led 13 0,0::C:0 led 14 0,0::C:0 led 15 0,0::C:0 led 16 0,0::C:0 led 17 0,0::C:0 led 18 0,0::C:0 led 19 0,0::C:0 led 20 0,0::C:0 led 21 0,0::C:0 led 22 0,0::C:0 led 23 0,0::C:0 led 24 0,0::C:0 led 25 0,0::C:0 led 26 0,0::C:0 led 27 0,0::C:0 led 28 0,0::C:0 led 29 0,0::C:0 led 30 0,0::C:0 led 31 0,0::C:0

color

color 0 0,0,0 color 1 0,255,255 color 2 0,0,255 color 3 30,0,255 color 4 60,0,255 color 5 90,0,255 color 6 120,0,255 color 7 150,0,255 color 8 180,0,255 color 9 210,0,255 color 10 240,0,255 color 11 270,0,255 color 12 300,0,255 color 13 330,0,255 color 14 0,0,0 color 15 0,0,0

mode_color

mode_color 0 0 1 mode_color 0 1 11 mode_color 0 2 2 mode_color 0 3 13 mode_color 0 4 10 mode_color 0 5 3 mode_color 1 0 5 mode_color 1 1 11 mode_color 1 2 3 mode_color 1 3 13 mode_color 1 4 10 mode_color 1 5 3 mode_color 2 0 10 mode_color 2 1 11 mode_color 2 2 4 mode_color 2 3 13 mode_color 2 4 10 mode_color 2 5 3 mode_color 3 0 8 mode_color 3 1 11 mode_color 3 2 4 mode_color 3 3 13 mode_color 3 4 10 mode_color 3 5 3 mode_color 4 0 7 mode_color 4 1 11 mode_color 4 2 3 mode_color 4 3 13 mode_color 4 4 10 mode_color 4 5 3 mode_color 5 0 9 mode_color 5 1 11 mode_color 5 2 2 mode_color 5 3 13 mode_color 5 4 10 mode_color 5 5 3 mode_color 6 0 6 mode_color 6 1 10 mode_color 6 2 1 mode_color 6 3 0 mode_color 6 4 0 mode_color 6 5 2 mode_color 6 6 3 mode_color 6 7 6 mode_color 6 8 0 mode_color 6 9 0 mode_color 6 10 0

set looptime = 2000 set i2c_overclock = OFF set gyro_sync = ON set gyro_sync_denom = 2 set acc_task_frequency = 500 set attitude_task_frequency = 250 set async_mode = NONE set mid_rc = 1500 set min_check = 1100 set max_check = 1900 set rssi_channel = 0 set rssi_scale = 30 set rssi_ppm_invert = OFF set rc_smoothing = ON set input_filtering_mode = OFF set min_throttle = 1150 set max_throttle = 1850 set min_command = 1000 set 3d_deadband_low = 1406 set 3d_deadband_high = 1514 set 3d_neutral = 1460 set 3d_deadband_throttle = 1000 set motor_pwm_rate = 400 set motor_pwm_protocol = STANDARD set fixed_wing_auto_arm = OFF set disarm_kill_switch = OFF set auto_disarm_delay = 30 set small_angle = 25 set reboot_character = 82 set gps_provider = UBLOX set gps_sbas_mode = NONE set gps_dyn_model = AIR_1G set gps_auto_config = ON set gps_auto_baud = ON set inav_auto_mag_decl = ON set inav_accz_unarmedcal = ON set inav_use_gps_velned = ON set inav_gps_delay = 200 set inav_gps_min_sats = 6 set inav_w_z_baro_p = 0.350 set inav_w_z_gps_p = 0.200 set inav_w_z_gps_v = 0.500 set inav_w_xy_gps_p = 1.000 set inav_w_xy_gps_v = 2.000 set inav_w_z_res_v = 0.500 set inav_w_xy_res_v = 0.500 set inav_w_acc_bias = 0.010 set inav_max_eph_epv = 1000.000 set inav_baro_epv = 100.000 set nav_disarm_on_landing = OFF set nav_use_midthr_for_althold = OFF set nav_extra_arming_safety = ON set nav_user_control_mode = ATTI set nav_position_timeout = 5 set nav_wp_radius = 100 set nav_max_speed = 700 set nav_max_climb_rate = 500 set nav_manual_speed = 500 set nav_manual_climb_rate = 200 set nav_landing_speed = 200 set nav_land_slowdown_minalt = 500 set nav_land_slowdown_maxalt = 2000 set nav_emerg_landing_speed = 500 set nav_min_rth_distance = 500 set nav_rth_tail_first = OFF set nav_rth_alt_mode = AT_LEAST set nav_rth_altitude = 1000 set nav_mc_bank_angle = 30 set nav_mc_hover_thr = 1500 set nav_mc_auto_disarm_delay = 2000 set nav_fw_cruise_thr = 1400 set nav_fw_min_thr = 1200 set nav_fw_max_thr = 1700 set nav_fw_bank_angle = 20 set nav_fw_climb_angle = 20 set nav_fw_dive_angle = 15 set nav_fw_pitch2thr = 10 set nav_fw_roll2pitch = 75 set nav_fw_loiter_radius = 5000 set nav_fw_launch_accel = 1863 set nav_fw_launch_detect_time = 40 set nav_fw_launch_thr = 1700 set nav_fw_launch_motor_delay = 500 set naw_fw_launch_timeout = 5000 set naw_fw_launch_climb_angle = 10 set serialrx_provider = IBUS set spektrum_sat_bind = 0 set telemetry_switch = OFF set telemetry_inversion = ON set frsky_default_lattitude = 0.000 set frsky_default_longitude = 0.000 set frsky_coordinates_format = 0 set frsky_unit = IMPERIAL set frsky_vfas_precision = 0 set frsky_vfas_cell_voltage = OFF set hott_alarm_sound_interval = 5 set smartport_uart_unidir = OFF set battery_capacity = 0 set vbat_scale = 110 set vbat_max_cell_voltage = 43 set vbat_min_cell_voltage = 33 set vbat_warning_cell_voltage = 35 set current_meter_scale = 400 set current_meter_offset = 0 set multiwii_current_meter_output = OFF set current_meter_type = ADC set align_gyro = DEFAULT set align_acc = DEFAULT set align_mag = CW270FLIP set align_board_roll = 0 set align_board_pitch = 0 set align_board_yaw = 0 set gyro_lpf = 42HZ set moron_threshold = 32 set imu_dcm_kp = 2500 set imu_dcm_ki = 50 set imu_dcm_kp_mag = 10000 set imu_dcm_ki_mag = 0 set pos_hold_deadband = 20 set alt_hold_deadband = 50 set yaw_motor_direction = 1 set yaw_jump_prevention_limit = 200 set tri_unarmed_servo = ON set servo_lowpass_freq = 400 set servo_lowpass_enable = OFF set servo_center_pulse = 1500 set servo_pwm_rate = 50 set failsafe_delay = 10 set failsafe_off_delay = 200 set failsafe_throttle = 1000 set failsafe_kill_switch = OFF set failsafe_throttle_low_delay = 100 set failsafe_procedure = SET-THR set rx_min_usec = 885 set rx_max_usec = 2115 set acc_hardware = 0 set baro_use_median_filter = ON set baro_hardware = 3 set mag_hardware = 2 set blackbox_rate_num = 1 set blackbox_rate_denom = 1 set blackbox_device = SDCARD set magzero_x = 54 set magzero_y = -24 set magzero_z = 130 set acczero_x = -19 set acczero_y = 22 set acczero_z = -97 set ledstrip_visual_beeper = OFF set accgain_x = 4093 set accgain_y = 4092 set accgain_z = 4071

rxfail

rxfail 0 a rxfail 1 a rxfail 2 a rxfail 3 a rxfail 4 h rxfail 5 h rxfail 6 h rxfail 7 h rxfail 8 h rxfail 9 h rxfail 10 h rxfail 11 h rxfail 12 h rxfail 13 h rxfail 14 h rxfail 15 h rxfail 16 h rxfail 17 h

digitalentity commented 6 years ago

No activity. Closing

iforce2d commented 6 years ago

Sorry, for some reason I thought I had replied already. I only saw this problem twice, at least I think it was the same problem both times but can't be sure. At this point I'm thinking it was due to a glitch in I2C communication between the FC and the external barometer, which briefly gave a reading of 14km altitude. It's possible that it was fixed by https://github.com/iNavFlight/inav/pull/1654 fwiw blackbox data and more info here: https://www.fc-forums.com/viewtopic.php?f=14&p=87