Home Forums Everything about the Tricopter V4 F3FC & iNav experiences

Viewing 15 posts - 91 through 105 (of 164 total)
  • Author
    Posts
  • #36127
    Marlon
    Participant

    Nobody bothered to hit me up for this? haha

    #36128
    Marlon
    Participant

    YOU ARE MY HERO!

    #36129
    Rob McKenzie
    Participant

    Did you have some success with iNav yourself #marlon?

    #36133
    Marlon
    Participant

    Hi ROB,

    Thanks for asking, after almost giving up on the hobby… Yesterday a friend showed me photo of his new RadioShack type micro quad. Saying “Oh this is great, and hovers very well” I said to my self… this is embarrassing. I have a tri with GPS BARO FPV MAG GYRO… and still I can’t fly. Putting iNav and Cleanflight never crossed my mind. UNTIL last night, I said lemme see if there is any new Triflight firmware… NADA NIENTE NOTHING. I’m already using 0.6RC1 (GPS support) so I said lemme try flashing something else here. I flashed the latest Cleanflight… and saw hmmm flashing other firmware than Triflight is no hassle.

    And then I stumbled upon this!!! I remember some one here telling me to try iNav before… I said NEH what is this, why try something with no Tricopter support! My last post was in October, and this tread started around the time I took off and said. This is nice but it’s not for me. DJI here I come. But even dormant… I kept ordering stuff for my shelf queen. Si I have a brand new minimOSD now. Not using the micros anymore… meh I don’t trust them. I’m using a NEW external UBEC now, cause my onboard BEC is whacky or fried (ordering a a new F3FC… next weekish DHL 2 days)

    Well Rob I flashed iNav before reading more than 3 lines!!! Like Wilco said this is a long story, a story you guys know, me my self have struggling with for months now. Like I said before GPS on MY tricopter is a MUST! I’m not a racer not a pro. Well DJI… YOU AINT GETTING MY MONEY… yet hahaha.

    I’ll be asking and reading on as I move along today. I’m goin to be here ALL DAY setting up iNav on my Tri today.

    1. I have already flashed iNav successfully: GPS is connection working OK
    2. Replacing broken MininOSD micro with MinmOSD now and 3D print skids: DONE it took a while cause I had
    to do a MAVlink-OSD 5V MOD.
    3. Must check my external MAG status, I have a Ublox7 Micro GPS with mag:
    4. Additional setting needed before I do a GPS hover test (after seeing DaveL video I was impressed
    he said he didn’t use any additional settings):

    Ok I’m at 2. now, hooking up the new MinimOSD any help and or heads up would be great guys.

    Attachments:
    #36135
    DaveL
    Participant

    Marlon!
    ‘Bout time, been waiting for you!
    Must read the Wiki, and get a better gps same as mine.
    I’m slammed by work today but will try to answer stuff as it comes up. I have a bunch of settings/CLI tweaks for you to change before you fly it.
    I still have to work on pids and make it smoother, but it does fly, chased this around on the weekend…

    #36140
    Marlon
    Participant

    HI DaveL,

    I’m happy to be BACK!!!

    #36144
    Marlon
    Participant

    2. Needed a crash course in MSP and MAVLink protocols. Cause the OSD gave me a Mavlink Heartbeat Error. All good now. I’m on MSP, OSD is working OK.
    3. My previous struggle had it already working. Maybe we can confirm this together: MAG and GPS lit BLUE, HMC5883 Magnetometer in Configuration, I2C errors 0. Pre-arming checks PASS PASS PASS PASS PASS PASS PASS
    4. Too late for a test now (too afraid hehehe): but any additional CLi settings and tips are welcome.

    Still can’t get the voltage to show up on the OSD. Another thing beeper is gone… it went with the onboard 5V. But strangely it worked one time after that while trying to make the MinimOSD micro work, CLI settings?

    Another thing i’m using the old DYS setup, cli settings applied. But what are esc settings for these. Oneshot…? Manual settings for the esc settings would be great. It’s on default atm.

    #36150
    DaveL
    Participant

    Marlon, start with the current iNav defaults (and save them so you can go back to check what the defaults were). Change the obvious things in iNav configurator, then look for these items in your CLI dump:

    feature PWM_OUTPUT_ENABLE [to enable the motors]
    
    set looptime = 2000
    set i2c_overclock = OFF
    set gyro_sync = ON
    set gyro_sync_denom = 1
    set acc_task_frequency = 500
    set attitude_task_frequency = 250
    set async_mode = GYRO
    
    set gyro_lpf = 188HZ
    
    set motor_pwm_rate = 2000
    set motor_pwm_protocol = ONESHOT125
    
    set nav_user_control_mode = CRUISE
    
    set align_mag = CW90 [depends on your compass]
    set mag_declination = -1030 [look up for your area, mine is -10.3]
    
    set nav_posr_d = 40 [to tame the poshold wobbles]
    

    Also grab kdiff3, makes easy to see what has been changed.

    #36156
    Marlon
    Participant

    Thanks DaveL,

    DONE I applied the cli settings. But around here: set align_mag = CW90 [depends on your compass]
    set mag_declination = -1030 [look up for your area, mine is -10.3] I became an “expert” hahaahaha I had these already set.

    What about failsafe… Land??? Or RTH… can it be trusted?

    #36157
    Marlon
    Participant

    Here is my CLI Dump:

    # version
    # INAV/RCEXPLORERF3 1.5.1 Jan 5 2017 / 11:36:06 (556168d)
    # pflags
    # Persistent config flags: 0x00000000
    # dump master

    # mixer
    mixer TRI
    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 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 20 1 115200 38400 0 115200
    serial 0 0 115200 38400 0 115200
    serial 1 1 115200 38400 0 115200
    serial 2 2 115200 57600 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 = 1
    set acc_task_frequency = 500
    set attitude_task_frequency = 250
    set async_mode = GYRO
    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 = 2000
    set motor_pwm_protocol = ONESHOT125
    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 = AUTO
    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 = CRUISE
    set nav_position_timeout = 5
    set nav_wp_radius = 100
    set nav_max_speed = 300
    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_climb_first = ON
    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_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_motor_delay = 500
    set nav_fw_launch_timeout = 5000
    set nav_fw_launch_climb_angle = 10
    set serialrx_provider = SBUS
    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 = ON
    set current_meter_type = ADC
    set align_gyro = DEFAULT
    set align_acc = CW180FLIP
    set align_mag = CW180FLIP
    set align_board_roll = 0
    set align_board_pitch = 0
    set align_board_yaw = 0
    set gyro_lpf = 188HZ
    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 = 5
    set failsafe_recovery_delay = 5
    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 = MPU6000
    set baro_use_median_filter = ON
    set baro_hardware = MS5611
    set mag_hardware = HMC5883
    set blackbox_rate_num = 1
    set blackbox_rate_denom = 1
    set blackbox_device = SERIAL
    set magzero_x = -12
    set magzero_y = -86
    set magzero_z = 108
    set acczero_x = 170
    set acczero_y = -67
    set acczero_z = -518
    set ledstrip_visual_beeper = OFF
    set accgain_x = 4073
    set accgain_y = 4111
    set accgain_z = 4031

    # rxfail
    rxfail 0 a
    rxfail 1 a
    rxfail 2 a
    rxfail 3 h
    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

    # dump profile

    # profile
    profile 0

    # aux
    aux 0 0 2 900 1100
    aux 1 1 0 1875 2100
    aux 2 2 0 1400 1600
    aux 3 3 3 1400 1600
    aux 4 9 3 925 1100
    aux 5 8 1 900 1100
    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
    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
    rxrange 0 1000 2000
    rxrange 1 1000 2000
    rxrange 2 1000 2000
    rxrange 3 1000 2000

    # servo
    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

    set nav_alt_p = 50
    set nav_alt_i = 0
    set nav_alt_d = 0
    set nav_vel_p = 100
    set nav_vel_i = 50
    set nav_vel_d = 10
    set nav_pos_p = 65
    set nav_pos_i = 120
    set nav_pos_d = 10
    set nav_posr_p = 180
    set nav_posr_i = 15
    set nav_posr_d = 40
    set nav_navr_p = 10
    set nav_navr_i = 5
    set nav_navr_d = 8
    set deadband = 5
    set yaw_deadband = 5
    set throttle_tilt_comp_str = 0
    set flaperon_throw_offset = 250
    set flaperon_throw_inverted = OFF
    set gimbal_mode = NORMAL
    set fw_iterm_throw_limit = 165
    set mode_range_logic_operator = OR
    set default_rate_profile = 0
    set mag_declination = 1120
    set mag_hold_rate_limit = 90
    set p_pitch = 43
    set i_pitch = 30
    set d_pitch = 26
    set p_roll = 49
    set i_roll = 30
    set d_roll = 48
    set p_yaw = 170
    set i_yaw = 45
    set d_yaw = 45
    set p_level = 20
    set i_level = 15
    set d_level = 75
    set max_angle_inclination_rll = 300
    set max_angle_inclination_pit = 300
    set gyro_soft_lpf_hz = 60
    set acc_soft_lpf_hz = 15
    set dterm_lpf_hz = 40
    set yaw_lpf_hz = 30
    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

    # dump rates

    # rateprofile
    rateprofile 0

    set rc_expo = 70
    set rc_yaw_expo = 20
    set thr_mid = 50
    set thr_expo = 0
    set roll_rate = 75
    set pitch_rate = 75
    set yaw_rate = 75
    set tpa_rate = 0
    set tpa_breakpoint = 1500

    #

    #36161
    Marlon
    Participant

    DaveL maybe you can help,

    I know now RSSI is a protocol between receiver and transmitter… But isn’t there any way I can get signal strength on my OSD? I have a Delta8 it has RSSI… I think it sends that data to a transmitter that supports it my 8J don’t supported RSSI. But to me it’s nice have that info on my OSD.

    Don’t know if it is related but after I applied your CLI setting I could not get a 3D fix… then I saw it was only after I got 6 Sats (indoors) I got a 3D fix and safe flight. I like that.

    #36167
    wilco1967
    Participant

    For those who still remember my first post about vibration issues, where I talked about soft mounting….
    Just found something interesting.
    Soft Mount Quadcopter Motors

    This is not exactly the same as I experienced, but very similar (my problem was alt-hold, caused by ACC_Z being affected by resonance).

    Anyway… just wanted to share.

    In the meantime, a few things happened over here…

    The F3FC on the old V3 got damaged in a crash, and since I still had some slight vibration problems even after soft-mouting the motors, I decided to try and mount the SPRF3 board which I had lying around….
    And hey, presto !…. All the vibration problems where gone (everything else remained the same). I mounted the SPRF3 on 4 nylon spacers. I could even remove the soft mounting of the motors, and all was perfect…. just the mounting of the SPRF3 on 4 nylon standoffs was apparently all the damping I needed.

    Just after Christmas, that old V3 was lost in a fly-away… Never found out how that happened. It was supposed to RTH, but it flew away into the unknown. Lost the copter with everything on it.
    So I ordered a new V4 from David with everything new, including the motors from the electronics pack… these are beautiful and run super smooth (zero crashes so far…)… highly recommended !

    But I still went for a separate flight controller (again a SPRF3Evo), instead of the integrated F3FC tricopter frame FC…I selected the old power distribution tricopter bottom plate. (please David, don’t completely stop selling them…. they certainly have their use).

    Probably a F3FC tricopter frame would have also done just fine (these new motors are sooo much smoother as the old beaten up ones before), but I didn’t want to take the gamble with vibrations (It WILL crash sooner or later, and motors won’t stay this smooth after a few crashes)….
    The wiring is less ‘clean’ now, but still looks OK… But more important, zero problems with vibrations. The blacklog files look a lot better than before.

    I still have the F3FC board lying around, and I think I could repair it (one track was lifted when an arm, including the wires, was ripped off), so maybe one day I might give it a try…
    But for now, the V4 is flying beautifully… never flew smoother.

    So if you haven’t done so, give iNav a try !

    #36170
    DaveL
    Participant

    Stupid soft-mounters Unite!
    Great video, thanks Wilco, it is “a big freekin deal”, especially for our hard-mounted FC’s!
    Do you have some insight into how to tame the PH-cruise wobbles? I’m only around 380 pages into the 700-page INAV thread (plus the recent stuff) and the suspense is killing me. Can you share a recent CLI dump ?

    Marlon,
    Trust the failsafe code, it works.
    But check your wiring and your solder joints and your CLI configuration.
    Plenty of ways for you and I to screw up, it’s a complicated machine and everything has to be right.
    Test carefully, so you can trust the system.
    I can shut off my tx and it will park itself on the launchpad.

    I just received my micro minimosd, so I don’t have experience with it yet, but I think you can get rssi direct from rx to osd.

    If I get a tune that I like, I’ll post up my CLI dump.

    #36175
    wilco1967
    Participant

    Here’s mine….
    Standard V4 tricopter, with the standard electronics set…

    Works pretty smooth (but different pilots have different tastes)
    Anyway, it will get you started.

    please note: I’ll post 2 versions…
    one older one, but for the F3FC (on a V3 tricopter with 9″ props)
    the newer one is for SPRF3evo I’m currently flying….
    but PID settings are similar…

    #36178
    wilco1967
    Participant

    regarding the fail safe code… It works indeed !
    As I lost my old V3 in a fly-away just a few weeks ago, I was particulary worried….

    just set your receiver to no-pulses, and VERIFY that works, even after a power cycle…
    in iNav, set your phase-2 failsafe to RTH.

    in CLI, make sure you have:
    set failsafe_recovery_delay = 5 (or some other SMALL number’)

    This failsafe recovery delay is not shown in the iNav configurator, so is easy to miss.
    Mine was set by default at 180 something (i.e. 18 seconds)…
    So it would take 18 seconds before I would regain control again after switching the transmitter back on.
    Now it will recover in 0.5 seconds (+ the delay for starting up the transmitter and re-linking of the receiver. TEST that on the bench before trying in real flight.

    On my first real fail-safe attempt, I set RTH to stay at the same altitude, and the speed to 100 cm/s… I tied my dog’s leash to the copter to ensure it wouldn’t do anything stupid after I switched off the transmitter, but all worked flawless…

    Now I trust it sufficient so I’m confident to switch-off my transmitter in mid flight, and have it return to me and land where it started…

    for RTH, I recommend to set nav_rth_alt_mode = AT_LEAST, and sufficient hight (nav_rth_altitude) to clear all obstacles (trees) around you.
    Another thing… in attached SPF3 file, nav_extra_arming_safety is set to off, but you should set it to on…. I did this to test things at home, when I don’t have a GPS lock… I always check myself to not take off before i have a valid lock.
    If you start without a GPS lock, it has no way of remembering where ‘home’ is, so RTH will not work if you need it…
    nav_extra_arming_safety = on stops you from arming/taking off if there is no GPS lock (and some other tests).

    BTW: the old F3FC file I posted, has NOT got all the failsafe settings correct (and it’s for an older version)… check the SPRF3 config.

    FYI:
    I never found out what caused the fly-away of my old V3… But I assume it was caused by the 433Mhz datalink I was using, that perhaps had overwritten the ‘home’ position when it was at the end of it’s range, and started sending nonsense commands.
    Not sure if that is really the cause, but anyway, the potential to overwrite the home position has now been removed in the latest iNav versions, so it shouldn’t be possible anymore, no matter how much ‘garbage’ is sent over the serial link.

Viewing 15 posts - 91 through 105 (of 164 total)
  • The forum ‘Everything about the Tricopter V4’ is closed to new topics and replies.