PosHold Flight Modes do not show up even with Optical Flow module configured
Current Behavior
I'm trying to set up Optical Flow sensor (Matek OpFlow module) in a GepRC F722 AIO (no baro, no mag, no GPS). The only way I can get PosHold and AltHold modes to appear is if I configure a fake gps port, but this means I need to bypass arming safeties every time I want to fly.
Steps to Reproduce
- Configure FC to run OpFlow module
- Attempt to set position hold/altitude hold modes (do not show up in modes tab)
Expected behavior
Be able to enable position hold when an OPFlow module with rangefinder is configured, since it is able to give a position and altitude setting
Suggested solution(s)
Not sure but perhaps be able to dynamically decide if position is coming from GPS or OpFlow + rangefinder modules and allow either as a valid 3D position source?
Additional context
diff all
version
INAV/GEPRC_F722_AIO 7.0.0 Mar 28 2024 / 20:06:38 (GITDIR-N)
GCC-10.3.1 20210824 (release)
start the command batch
batch start
reset configuration to default settings
defaults noreboot
resources
Timer overrides
Outputs [servo]
safehome
features
feature PWM_OUTPUT_ENABLE
beeper
blackbox
blackbox -NAV_ACC blackbox NAV_POS blackbox NAV_PID blackbox MAG blackbox ACC blackbox ATTI blackbox RC_DATA blackbox RC_COMMAND blackbox MOTORS blackbox -GYRO_RAW blackbox -PEAKS_R blackbox -PEAKS_P blackbox -PEAKS_Y
Receiver: Channel map
Ports
serial 0 2097152 115200 115200 0 115200 serial 4 1 115200 115200 0 115200
LEDs
LED color
LED mode_color
Modes [aux]
aux 0 0 0 1700 2100 aux 1 1 1 1300 2100 aux 2 11 1 1700 2100 aux 3 3 1 1700 2100 aux 4 5 1 1700 2100 aux 5 52 3 1700 2100 aux 6 38 3 900 1300 aux 7 47 2 1700 2100
Adjustments [adjrange]
Receiver rxrange
temp_sensor
Mission Control Waypoints [wp]
#wp 0 invalid
OSD [osd_layout]
Programming: logic
Programming: global variables
Programming: PID controllers
master
set looptime = 500 set gyro_main_lpf_hz = 90 set gyro_main_lpf_type = PT1 set dynamic_gyro_notch_q = 250 set dynamic_gyro_notch_min_hz = 70 set setpoint_kalman_q = 200 set gyro_zero_x = -6 set gyro_zero_y = 2 set gyro_zero_z = 2 set ins_gravity_cmss = 976.199 set acc_hardware = ICM42605 set acczero_x = 16 set acczero_y = -55 set acczero_z = 42 set accgain_x = 4320 set accgain_y = 3845 set rangefinder_hardware = MSP set opflow_hardware = MSP set opflow_scale = 8.621 set align_mag = CW270FLIP set mag_hardware = NONE set baro_hardware = NONE set serialrx_provider = CRSF set blackbox_rate_denom = 2 set motor_pwm_protocol = DSHOT300 set motor_poles = 12 set failsafe_procedure = DROP set align_board_roll = 1800 set align_board_yaw = 450 set applied_defaults = 6 set airmode_type = THROTTLE_THRESHOLD set inav_use_gps_no_baro = ON set inav_allow_dead_reckoning = ON set nav_user_control_mode = CRUISE set debug_mode = FLOW_RAW
mixer_profile
mixer_profile 1
set motor_direction_inverted = ON set model_preview_type = 3
Mixer: motor mixer
mmix reset
mmix 0 1.000 1.000 1.000 1.000 mmix 1 1.000 1.000 -1.000 -1.000 mmix 2 1.000 -1.000 1.000 -1.000 mmix 3 1.000 -1.000 -1.000 1.000
Mixer: servo mixer
mixer_profile
mixer_profile 2
Mixer: motor mixer
Mixer: servo mixer
profile
profile 1
set mc_p_pitch = 32 set mc_i_pitch = 90 set mc_d_pitch = 25 set mc_p_roll = 28 set mc_i_roll = 80 set mc_p_yaw = 30 set mc_i_yaw = 80 set dterm_lpf_hz = 85 set dterm_lpf_type = PT3 set nav_mc_vel_z_p = 150 set nav_mc_vel_z_i = 250 set nav_mc_vel_z_d = 25 set nav_mc_pos_xy_p = 80 set nav_mc_vel_xy_p = 50 set nav_mc_vel_xy_i = 40 set nav_mc_vel_xy_d = 60 set d_boost_min = 1.000 set d_boost_max = 1.000 set antigravity_gain = 2.000 set antigravity_accelerator = 5.000 set smith_predictor_delay = 1.500 set tpa_rate = 20 set tpa_breakpoint = 1200 set rc_expo = 75 set rc_yaw_expo = 75 set roll_rate = 70 set pitch_rate = 70 set yaw_rate = 60
profile
profile 2
profile
profile 3
battery_profile
battery_profile 1
set throttle_idle = 5.000
battery_profile
battery_profile 2
battery_profile
battery_profile 3
restore original profile selection
mixer_profile 1 profile 1 battery_profile 1
save configuration
save
You need a magnetometer for POSHOLD even with Opt Flow.
You need a magnetometer for POSHOLD even with Opt Flow.
Can you tell me why that is? I am using MTF-01 on an Eachine Tyro69 quadcopter with MATEKF411 board with only an accelerometer (MPU600) and no other sensor on the board. I have the same issue. In principal optical flow sensor that I use can measure the changes in heading and the changes in altitude. Just like a set of GPS and compass sensor would do. Is there a way I can use poshold with my setup?