- initial frequency peak tracking SNR increased from 10->15 db
- after initial detection the threshold decreases to SNR 5db
- gyro_fft large method refactored into smaller pieces
- sensors/vehicle_angular_velocity: dynamic notch FFT make sample rate
check a percentage and relax lower bound safety threshold
Using mixers on the IO side had a remote benefit of being able to
override all control surfaces with a radio remote on a fixed wing.
This ended up not being used that much and since the original design
10 years ago (2011) we have been able to convince ourselves that the
overall system stability is at a level where this marginal benefit,
which is not present on multicopters, is not worth the hazzle.
Co-authored-by: Beat Küng <beat-kueng@gmx.net>
Co-authored-by: Daniel Agar <daniel@agar.ca>
- change default FFT length (1024 -> 512)
- this doubles the update rate because half the number of samples are required for each
- decrease number of peaks (4 -> 3)
- so far 3 seems to be sufficient on most vehicles
- increase median filter window (3 -> 5)
- decrease SNR requirement (likely needs to be configurable)
- the ekf2 frontend typically runs in the background for up to 30 seconds waiting for all instances to appear, but this isn't supported by the legacy posix launcher
UART is the primary interface for telemetry radio: https://docs.emlid.com/navio2/ardupilot/hardware-setup/#uart-radio
Check first if /dev/ttyUSB0 exists (https://docs.emlid.com/navio2/ardupilot/hardware-setup/#usb-radio); if not, fall back to configuring over UART (/dev/ttyAMA0).
Use stricter check for character special file (-c) rather than just file (-f).
'console=serial0,115200' needs to be removed from /cmdline.txt as additional configuration step. This should be documented in the Navio2 section of docs.px4.io. Presumably, this is already performed as part of the Raspberry Pi OS prebuilt image Emlid spins.
- skip avionics rail voltage check when USB connected
- skip forced reboot on USB disconnect if circuit breaker set
- avionics voltage preflight check don't silently fail if system_power unavailble
- explicitly set supply check circuit breaker (CBRK_SUPPLY_CHK)
- always check with state machine before reboot/shutdown
- respect BOARD_HAS_POWER_CONTROL (shutdown from command, low battery, power button)
- px4_shutdown_request add optional delay and always execute from HPWORK
- px4_shutdown_request split out px4_reboot_request
Removes the calibration on startup, as these values were overwritten by
the system calibration values anyway.
So the only difference is that if all calibration scales were equal to 1,
the driver startup would have failed.
* MC_HTE: unitialize with hover_thrust parameter
* MC_HTE: constrain hover thrust setter between 0.1 and 0.9
* MC_HTE: integrate with land detector and velocity controller
* MCHoverThrustEstimator: Always publish an estimate even when not fusing measurements. This is required as the land detector and the position controller need to receive a hover thrust value.
* MC_HTE: use altitude agl threshold to start the estimator
local_position.z is relative to the origin of the EKF while dist_bottom
is above ground
Co-authored-by: bresch <brescianimathieu@gmail.com>
The bulk of this change was tightly coupled and needed to be deleted in one pass. Some of the smaller changes were things that broke as a result of the initial purge and subsequently fixed by further eradicating unnecessary platform differences. Finally, I deleted any dead code I came across in the related files I touched while going through everything.
- DriverFramework (src/lib/DriverFramework submodule) completely removed
- added dspal submodule in qurt platform (was brought in via DriverFramework)
- all df wrapper drivers removed
- all boards using df wrapper drivers updated to use in tree equivalents
- unused empty arch/board.h on posix and qurt removed
- unused IOCTLs removed (pub block, priv, etc)
- Integrator delete methods only used from df wrapper drivers
- commander: sensor calibration use "NuttX version" everywhere for now
- sensors: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
- battery_status: update to px4_{open, read, close} instead of DevMgr wrapper (adc open for analog differential pressure)
- cdev cleanup conflicting typedefs and names with actual OS (pollevent_t, etc)
- load_mon and top remove from linux boards (unused)
- delete unused PX4_MAIN_FUNCTION
- delete unused getreg32 macro
- delete unused SIOCDEVPRIVATE define
- named each platform tasks consistently
- posix list_devices and list_topics removed (list_files now shows all virtual files)