Closed VoicOfReason closed 6 years ago
I had a similar problems with the F4 FC affecting the Magnetometer in the GPS module. I would test the Mag operation on a bench by checking proper Mag readings at 0,90, 180, and 270 degrees. Also make sure when rotating the quad, that the mag reads and properly tracks the quad yaw rotation and immediately stops when the rotation stops. I was able to fix this in both of my quads by isolating the Mag from the FC. In one of the quads I was able to isolate the GPS/MAG using a brass shield. I believe this is the best approach as brass has no magnetic properties. In the other quad I was able to isolate the FC by placing a mumetal shield over the FC, but since mumetal is magnetic the GPS with MAG has to be located at least 15mm above the shield.
Could you show me where to find a brass shield? Picture? My flight controller is far away from the mag, about 6 inches.
Let's postulate that it isn't a mag issue since my mag is pretty far from the FC. What specific inav PID settings would I look at to get my quad to lock in its position quicker during hover (RTH is working fine)?
Toilet-bowling effect is in 99% cases a compass issue. Please verify that when you point your quad North heading shows 0 deg, East - 90 deg, South 180 deg, West 270 deg and values don't change more than 5 deg when you pitch/roll the machine up to 45 deg.
Yes, that is all correct in terms of degrees based on direction. It's actually NOT a toilet bowl. It is just sluggish in terms of stopping itself when moving around with alt/mag hold both turned on. At worst, it is a pendulum (left and right swinging until coming to rest). I had the toilet bowl last summer and I never solved that problem until switching FC's. However, in this case, I'm getting a solid hover in all directions even in wind, but if I MOVE around with alt/pos hold on, then it sways before coming to rest at its new position. Hope this is clear now what my issue is. I'm looking for specific settings to look at, e.g. set nav_mc_vel_xy_i = 45, etc.
@VoicOfReason Ah, I see. How big is your machine? Swinging might be an indication that the code is expecting the machine to do very rapid corrections which it is unable to satisfy. In that case you may try reducing PosXY P and VelXY P
Excellent. Will try.
I'm having the same symptoms. iNAV on a 250 sized quad with NEO8N GPS 18-19 locked sats. In fast forward flight it flares, goes back to approximate where I let off on the pitch and swings around to the point. It isn't as solid and rock steady as a Phantom 3 pro when letting the sticks go. I read the doc on PosPIDs and Vel PIDs but I don't understand the relationship and what effects they have. I'd appreciate any insight. Mahalo!
I’m still struggling to fix this but I’ve made a little progress adjusting Various P values. Let me know what progress your making...
What looptime are you running? @VoicOfReason @rennster12
looptime at 2000 My hardware is a 250 sized quad with a FLIP32 AIO. I believe it is an F1 chip. I understand it is dated. Here is the complete dump:
mixer QUADX
mmix reset
servo 0 1000 2000 1500 90 90 100 -1 servo 1 1000 2000 1500 90 90 100 -1 servo 2 1000 2000 1500 90 90 100 -1 servo 3 1000 2000 1500 90 90 100 -1 servo 4 1000 2000 1500 90 90 100 -1 servo 5 1000 2000 1500 90 90 100 -1 servo 6 1000 2000 1500 90 90 100 -1 servo 7 1000 2000 1500 90 90 100 -1 smix reset
feature -RX_PPM feature -VBAT feature -RX_SERIAL feature -MOTOR_STOP feature -SERVO_TILT feature -SOFTSERIAL feature -GPS feature -TELEMETRY feature -CURRENT_METER feature -3D feature -RX_PARALLEL_PWM feature -RX_MSP feature -RSSI_ADC feature -LED_STRIP feature -DASHBOARD 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 CURRENT_METER feature DASHBOARD feature PWM_OUTPUT_ENABLE 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 ACTION_SUCCESS beeper ACTION_FAIL beeper READY_BEEP beeper MULTI_BEEPS beeper DISARM_REPEAT beeper ARMED beeper SYSTEM_INIT beeper ON_USB beeper LAUNCH_MODE map AETR1234 serial 0 1 115200 38400 0 115200 serial 1 2 115200 115200 0 115200 aux 0 2 0 1450 1600 aux 1 3 0 1950 2100 aux 2 9 0 1950 2100 aux 3 18 2 950 1050 aux 4 0 0 900 900 aux 5 0 0 900 900 aux 6 0 0 900 900 aux 7 0 0 900 900 aux 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 900 900 aux 13 0 0 900 900 aux 14 0 0 900 900 aux 15 0 0 900 900 aux 16 0 0 900 900 aux 17 0 0 900 900 aux 18 0 0 900 900 aux 19 0 0 900 900 adjrange 0 0 0 900 900 0 0 adjrange 1 0 0 900 900 0 0 adjrange 2 0 0 900 900 0 0 adjrange 3 0 0 900 900 0 0 adjrange 4 0 0 900 900 0 0 adjrange 5 0 0 900 900 0 0 adjrange 6 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 adjrange 10 0 0 900 900 0 0 adjrange 11 0 0 900 900 0 0 rxrange 0 1000 2000 rxrange 1 1000 2000 rxrange 2 1000 2000 rxrange 3 1000 2000 set looptime = 2000 set gyro_sync = ON set gyro_sync_denom = 2 set align_gyro = DEFAULT set gyro_hardware_lpf = 188HZ set gyro_lpf_hz = 90 set moron_threshold = 32 set align_acc = DEFAULT set acc_hardware = MPU6050 set acc_lpf_hz = 15 set acczero_x = 138 set acczero_y = -52 set acczero_z = 34 set accgain_x = 4087 set accgain_y = 4122 set accgain_z = 4048 set align_mag = CW270FLIP set mag_hardware = HMC5883 set mag_declination = 930 set magzero_x = 44 set magzero_y = -39 set magzero_z = -7 set mag_hold_rate_limit = 90 set mag_calibration_time = 30 set baro_hardware = MS5611 set baro_use_median_filter = ON set mid_rc = 1500 set min_check = 1100 set max_check = 1900 set rssi_channel = 0 set rssi_scale = 30 set rssi_invert = OFF set rc_smoothing = ON set serialrx_provider = SPEK1024 set sbus_inversion = ON set spektrum_sat_bind = 0 set rx_min_usec = 850 set rx_max_usec = 2150 set rx_nosignal_throttle = HOLD set blackbox_rate_num = 1 set blackbox_rate_denom = 1 set blackbox_device = SERIAL set min_throttle = 1000 set max_throttle = 2000 set min_command = 1000 set motor_pwm_rate = 400 set motor_pwm_protocol = ONESHOT125 set failsafe_delay = 10 set failsafe_recovery_delay = 5 set failsafe_off_delay = 100 set failsafe_kill_switch = OFF set failsafe_throttle = 1500 set failsafe_throttle_low_delay = 100 set failsafe_procedure = SET-THR set failsafe_stick_threshold = 50 set failsafe_fw_roll_angle = -200 set failsafe_fw_pitch_angle = 100 set failsafe_fw_yaw_rate = -45 set align_board_roll = 0 set align_board_pitch = 0 set align_board_yaw = 0 set gimbal_mode = NORMAL set battery_capacity = 0 set vbat_scale = 111 set vbat_max_cell_voltage = 43 set vbat_min_cell_voltage = 33 set vbat_warning_cell_voltage = 34 set current_meter_scale = 400 set current_meter_offset = 0 set multiwii_current_meter_output = OFF set current_meter_type = ADC set yaw_motor_direction = 1 set yaw_jump_prevention_limit = 200 set 3d_deadband_low = 1490 set 3d_deadband_high = 1510 set 3d_neutral = 1500 set servo_center_pulse = 1500 set servo_pwm_rate = 50 set servo_lpf_hz = 20 set flaperon_throw_offset = 250 set flaperon_throw_inverted = OFF set tri_unarmed_servo = ON set reboot_character = 82 set imu_dcm_kp = 2500 set imu_dcm_ki = 50 set imu_dcm_kp_mag = 10000 set imu_dcm_ki_mag = 0 set small_angle = 25 set fixed_wing_auto_arm = OFF set disarm_kill_switch = OFF set auto_disarm_delay = 5 set gps_provider = UBLOX set gps_sbas_mode = AUTO set gps_dyn_model = AIR_1G set gps_auto_config = ON set gps_auto_baud = ON set gps_min_sats = 6 set deadband = 5 set yaw_deadband = 8 set pos_hold_deadband = 20 set alt_hold_deadband = 50 set 3d_deadband_throttle = 50 set inav_accz_unarmedcal = ON set inav_use_gps_velned = OFF set inav_gps_delay = 50 set inav_reset_altitude = NEVER 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 = 1.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 = ON set nav_extra_arming_safety = ON set nav_user_control_mode = CRUISE set nav_position_timeout = 5 set nav_wp_radius = 100 set nav_wp_safe_distance = 10000 set nav_max_speed = 2000 set nav_max_climb_rate = 2000 set nav_manual_speed = 2000 set nav_manual_climb_rate = 2000 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_climb_first = ON set nav_rth_climb_ignore_emerg = OFF set nav_rth_tail_first = OFF set nav_rth_allow_landing = ON set nav_rth_alt_mode = AT_LEAST set nav_rth_abort_threshold = 50000 set nav_rth_altitude = 1000 set nav_mc_bank_angle = 45 set nav_mc_hover_thr = 1400 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_velocity = 300 set nav_fw_launch_accel = 1863 set nav_fw_launch_detect_time = 40 set nav_fw_launch_thr = 1700 set nav_fw_launch_idle_thr = 1000 set nav_fw_launch_motor_delay = 500 set nav_fw_launch_spinup_time = 100 set nav_fw_launch_timeout = 5000 set nav_fw_launch_climb_angle = 18 set telemetry_switch = OFF set telemetry_inversion = OFF 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 ibus_telemetry_type = 0 set i2c_overclock = OFF set debug_mode = NONE set throttle_tilt_comp_str = 0 set input_filtering_mode = OFF set mode_range_logic_operator = OR profile 1
set mc_p_pitch = 60 set mc_i_pitch = 50 set mc_d_pitch = 20 set mc_p_roll = 45 set mc_i_roll = 40 set mc_d_roll = 20 set mc_p_yaw = 60 set mc_i_yaw = 45 set mc_d_yaw = 0 set mc_p_level = 20 set mc_i_level = 15 set mc_d_level = 75 set fw_p_pitch = 20 set fw_i_pitch = 35 set fw_ff_pitch = 10 set fw_p_roll = 25 set fw_i_roll = 35 set fw_ff_roll = 10 set fw_p_yaw = 50 set fw_i_yaw = 45 set fw_ff_yaw = 0 set fw_p_level = 20 set fw_i_level = 15 set fw_d_level = 75 set max_angle_inclination_rll = 300 set max_angle_inclination_pit = 300 set dterm_lpf_hz = 80 set yaw_lpf_hz = 30 set dterm_setpoint_weight = 0.000 set fw_iterm_throw_limit = 165 set pidsum_limit = 500 set yaw_p_limit = 300 set iterm_ignore_threshold = 200 set yaw_iterm_ignore_threshold = 50 set rate_accel_limit_roll_pitch = 0 set rate_accel_limit_yaw = 10000 set nav_mc_pos_z_p = 50 set nav_mc_pos_z_i = 0 set nav_mc_pos_z_d = 0 set nav_mc_vel_z_p = 100 set nav_mc_vel_z_i = 50 set nav_mc_vel_z_d = 10 set nav_mc_pos_xy_p = 65 set nav_mc_pos_xy_i = 120 set nav_mc_pos_xy_d = 10 set nav_mc_vel_xy_p = 120 set nav_mc_vel_xy_i = 15 set nav_mc_vel_xy_d = 100 set nav_fw_pos_z_p = 50 set nav_fw_pos_z_i = 0 set nav_fw_pos_z_d = 0 set nav_fw_pos_xy_p = 75 set nav_fw_pos_xy_i = 5 set nav_fw_pos_xy_d = 8 set rc_expo = 70 set rc_yaw_expo = 20 set thr_mid = 50 set thr_expo = 0 set roll_rate = 65 set pitch_rate = 65 set yaw_rate = 45 set tpa_rate = 0 set tpa_breakpoint = 1500
I noticed significant improvement when I used the 250 preset and set GPS to 50 delay. So far it is better than the large toilet bowling when I released the pitch.
Has anybody found a perfect solution for this issue? I have this with a 330 quad and a kakutef4. Thanks
I'm still having the issue.
On Thu, Apr 12, 2018 at 8:17 AM, danylam notifications@github.com wrote:
Has anybody found a perfect solution for this issue? I have this with a 330 quad and a kakutef4. Thanks
— You are receiving this because you were mentioned. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/2476#issuecomment-380801586, or mute the thread https://github.com/notifications/unsubscribe-auth/AAq5OS0XyGLSoKSGf3NHaz1a7_tUQOZ4ks5tn1QAgaJpZM4QcpOE .
hiy guys, I have a pretty good news for this so called pendulum swing or toilet bowl effect or circular drift etc... I got my quad with these specs:
FIRMWARE: INAV 1.8
I also struggled to make it stable on PosHold and RTH. I recalibrate compass and acc just to see what progress I have but it stays the same, :( then I realize that I really need to pay attention to my PID.
I input these PID settings: Roll 30 20 70 Pitch 30 20 70 Yaw 100 40 0
PosXY 65 120 - VelXY 180 15 5 Surface 10 5 8
ROLL, PITCH and YAW rate: 65
Modes: ANGLE for POSHOLD and RTH. And ALTHOLD combined with POSHOLD.
And all of the sudden, I got what I'm dreaming for. :) A rock steady GPS 250 quad for both Poshold and RTH. Now you try guys and please let me know.
This issue / pull request has been automatically marked as stale because it has not had any activity in 60 days. The resources of the INAV team are limited, and so we are asking for your help. This issue / pull request will be closed if no further activity occurs within two weeks.
Automatically closing as inactive.
I apologize if this issue would be better addressed in a different forum, but I trust the expertise of those here. I've tried many different options but I'm getting a pendulum type swing the slowly comes to a stop when moving around and then stopping with GPS pos/alt hold both turned on. I first noticed this last summer on an iNav quad I built and never fixed, giving up on solving the issue for awhile. Now, I have a FC without an internal mag (Omnibus F4 V3). It's not really a toilet bowl, but it just sort of swing leisurely back and forth a bit before coming to a stop. Once it stops, it hovers in place fairly well. I'm wondering if this is a bug or if there is a specific PID setting that needs to change since I've been messing with all of them with no success.
I'm seeing this "swing" effect in angle mode. Of course, I fly FPV in acro/rate mode. Thanks.