-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Developer info
Position estimator is a vital component for navigation subsystem. It takes data from all available sensors and fuses them together to figure out coordinates and velocities in the local frame of reference. All navigational decisions are made based on estimated position/velocity data.
It is currently desined for multirotors.
The key sensor for INAV is an accelerometer. Measured acceleration is translated from body-fixed frame to local NEU coordinates and integrated to yield velocities in North, East and Up directions. Velocity is further integrated to produce coordinates.
As accelerometer tend to drift, estimated velocities and coordinates tend to drift as well. This accumulated error is corrected from various reference sources - GPS, BARO, SONAR. Position estimator also maintains estimated position error for horizontal (X-Y) and vertical (Z) position.
When reference source is not available for some reason, estimated position error increases until it reaches a certain threshold. Beyond that threshold position is no longer updated and marked invalid until a valid reference source is available avain. This allows, for example, to fly through short (measured in seconds) GPS outages.
Using multiple sensors for estimation allows to filter noisy data (e.g. from barometer), interpolate between rare readings (e.g. from GPS), and immediately react on fast motion changes (using accelerometers) in the same time.
The following reference sources (with corresponding parameters for weight) are available for altitude and climb rate:
- Barometer - altitude (inav_w_z_baro_p)
- Barometer - velocity (inav_w_z_baro_v)
- Sonar - altitude (inav_w_z_sonar_p)
- Sonar - velocity (inav_w_z_sonar_v)
- GPS - altitude (inav_w_z_gps_p)
- GPS - velocity (inav_w_z_gps_v)
Sonar is optional source, it's only used when available and valid data received. GPS altitude is very noisy and is limited to FIXED_WING aircraft (experimental and untested).
The following reference sources (with corresponding parameters for weight) are available for position and velocity:
- GPS - position (inav_w_xy_gps_p)
- GPS - velocity (inav_w_xy_gps_v)
-
Enable dead reckoning (inav_enable_dead_reckoning)
-
Dead reckoning - position (inav_w_xy_dr_p)
-
Dead reckoning - velocity (inav_w_xy_dr_v)
-
Velocity decay rate, XY-axis (inav_w_xy_res_v)
-
Velocity decay rate, Z-axis (inav_w_z_res_v)
- Maximum acceptable position error (inav_max_eph_epv)
- Position error for SONAR sensor (inav_sonar_epv)
- Position error for BARO sensor (inav_baro_epv)
GPS data is not updated instantly. GPS module needs time to calculate new position and velocity. INAV has means of compensating for this delay. Expected GPS delay in milliseconds is controlled by inav_gps_delay_ms parameter. Typical value for GPS delay is 200ms.
ALTHOLD mode uses two PIDs - ALT and VEL. Navigation Z-controller functional diagram is shown below:
Actually ALT PID parameters control two P-controllers: Position-to-Velocity and Velocity-to-Acceleration
- ALT_P - defines how fast quad will attempt to compensate for altitude error, converts altitude error to desired vertical velocity (climb rate)
- ALT_I - not used
- ALT_D - not used
This PID-controller is an Acceleration-to-Throttle controller
- VEL_P - defined how much throttle quad will add/reduce to achieve desired velocity
- VEL_I - controls compensation for hover throttle (and vertical air movement, thermals). This can be zero if hover throttle is precisely 1500us. Too much VEL I will lead to vertical oscillations, too low VEL I will cause drops or jumps when ALTHOLD is enabled, very low VEL I can result in total inability to maintain altitude
- VEL_D - acts as a dampener for acceleration. VEL D will resist any velocity change regardless of its nature (requested by VEL P and VEL I or induced by wind).
XY-controller uses two PIDs - POS and POSR
This is a Position-to-Velocity P-controller active in POSHOLD, RTH and WP modes
- POS_P - translates position error to desired velocity to reach the target
- POS_I - not used
- POS_D - not used
Position rate PID-controller, controls Velocity-to-Acceleration
- POSR_P - controls acceleration to achieve desired velocity
- POSR_I - controls compensation for side wind or other disturbances. In totally calm air POSR I can be close to zero
- POSR_D - dampens response from P and I components; Tests indicate that this one can be zero at all times
Output of POSR PID-controller is desired acceleration which is directly translated to desired lean angles.
Navigation operates in 3 different coordinate systems.
Represents position on or above earth with a latitude, longitude and height value. Height is defined as altitude above the mean sea level.
- The x axis is aligned with the vector to the north pole (tangent to meridians).
- The y axis points to the east side (tangent to parallels)
- The z axis points up from the center of the earth
This is a classical cartesian coordinate system where the 3 axes are orthogonal to each other.
The units for the NEU coordinate system are centimetres.
This frame of reference defines coordinates in LLH coordinate system. This frame of reference is not used directly by the code and is provided as an interface for defining waypoints and receiving reference data from GPS.
This frame of reference defines coordinate in NEU coordinate system relative to a GPS Origin point. GPS origin is defined as a point where GPS fix with sufficient accuracy was firstly acquired. GPS Origin is usually a point of launch. Most calculations are done in this frame of reference.
Attached to the aircraft.
- The x axis points in forward direction (as defined by geometry and not by movement) (roll axis, +ve to right)
- The y axis points to the right (geometrically) (pitch axis, +ve nose down, an INAV anomaly to convention)
- The z axis points upwards (geometrically) (yaw axis, +ve nose to right)
This frame of reference is used to read sensor data and calculate lean angles. Usually the only operations in this frame of reference are coordinate transformations to/from local frame of reference.
INAV Version Release Notes
7.1.0 Release Notes
7.0.0 Release Notes
6.0.0 Release Notes
5.1 Release notes
5.0.0 Release Notes
4.1.0 Release Notes
4.0.0 Release Notes
3.0.0 Release Notes
2.6.0 Release Notes
2.5.1 Release notes
2.5.0 Release Notes
2.4.0 Release Notes
2.3.0 Release Notes
2.2.1 Release Notes
2.2.0 Release Notes
2.1.0 Release Notes
2.0.0 Release Notes
1.9.1 Release notes
1.9.0 Release notes
1.8.0 Release notes
1.7.3 Release notes
Older Release Notes
QUICK START GUIDES
Getting started with iNav
Fixed Wing Guide
Howto: CC3D flight controller, minimOSD , telemetry and GPS for fixed wing
Howto: CC3D flight controller, minimOSD, GPS and LTM telemetry for fixed wing
INAV for BetaFlight users
launch mode
Multirotor guide
YouTube video guides
DevDocs Getting Started.md
DevDocs INAV_Fixed_Wing_Setup_Guide.pdf
DevDocs Safety.md
Connecting to INAV
Bluetooth setup to configure your flight controller
DevDocs Wireless Connections (BLE, TCP and UDP).md\
Flashing and Upgrading
Boards, Targets and PWM allocations
Upgrading from an older version of INAV to the current version
DevDocs Installation.md
DevDocs USB Flashing.md
Setup Tab
Live 3D Graphic & Pre-Arming Checks
Calibration Tab
Accelerometer, Compass, & Optic Flow Calibration
Alignment Tool Tab
Adjust mount angle of FC & Compass
Ports Tab
Map Devices to UART Serial Ports
Receiver Tab
Set protocol and channel mapping
Mixer
Outputs
DevDocs ESC and servo outputs.md
DevDocs Servo.md
Modes
Modes
Navigation modes
Navigation Mode: Return to Home
DevDocs Controls.md
DevDocs INAV_Modes.pdf
DevDocs Navigation.md
Configuration
Failsafe
Failsafe
DevDocs Failsafe.md
PID Tuning
PID Attenuation and scaling
Fixed Wing Tuning for INAV 3.0
Tune INAV PIFF controller for fixedwing
DevDocs Autotune - fixedwing.md
DevDocs INAV PID Controller.md
DevDocs INAV_Wing_Tuning_Masterclass.pdf
DevDocs PID tuning.md
DevDocs Profiles.md
OSD and VTx
DevDocs Betaflight 4.3 compatible OSD.md
OSD custom messages
OSD Hud and ESP32 radars
DevDocs OSD.md
DevDocs VTx.md
LED Strip
DevDocs LedStrip.md
Advanced Tuning
Programming
DevDocs Programming Framework.md
Adjustments
DevDocs Inflight Adjustments.md
Mission Control
iNavFlight Missions
DevDocs Safehomes.md
Tethered Logging
Log when FC is connected via USB
Blackbox
DevDocs Blackbox.md
INAV blackbox variables
DevDocs USB_Mass_Storage_(MSC)_mode.md
CLI
iNav CLI variables
DevDocs Cli.md
DevDocs Settings.md
VTOL
DevDocs MixerProfile.md
DevDocs VTOL.md
TROUBLESHOOTING
"Something" is disabled Reasons
Blinkenlights
Pixel OSD FAQs
TROUBLESHOOTING
Why do I have limited servo throw in my airplane
ADTL TOPICS, FEATURES, DEV INFO
AAT Automatic Antenna Tracker
Building custom firmware
Default values for different type of aircrafts
Features safe to add and remove to fit your needs.
Developer info
INAV MSP frames changelog
INAV Remote Management, Control and Telemetry
Lightweight Telemetry (LTM)
Making a new Virtualbox to make your own INAV
MSP Navigation Messages
MSP V2
OrangeRX LRS RX and OMNIBUS F4
Rate Dynamics
Target and Sensor support
UAV Interconnect Bus
Ublox 3.01 firmware and Galileo
DevDocs 1wire.md
DevDocs ADSB.md
DevDocs Battery.md
DevDocs Buzzer.md
DevDocs Channel forwarding.md
DevDocs Display.md
DevDocs Fixed Wing Landing.md
DevDocs GPS_fix_estimation.md
DevDocs LED pin PWM.md
DevDocs Lights.md
DevDocs OSD Joystick.md
DevDocs Servo Gimbal.md
DevDocs Temperature sensors.md
OLD LEGACY INFO
Supported boards
DevDocs Boards.md
Legacy Mixers
Legacy target ChebuzzF3
Legacy target Colibri RACE
Legacy target Motolab
Legacy target Omnibus F3
Legacy target Paris Air Hero 32
Legacy target Paris Air Hero 32 F3
Legacy target Sparky
Legacy target SPRacingF3
Legacy target SPRacingF3EVO
Legacy target SPRacingF3EVO_1SS
DevDocs Configuration.md
Request form new PRESET
DevDocs Introduction.md
Welcome to INAV, useful links and products
iNav Telemetry
DevDocs Rangefinder.md
DevDocs Rssi.md
DevDocs Runcam device.md
DevDocs Serial.md
DevDocs Telemetry.md
DevDocs Rx.md
DevDocs Spektrum bind.md