mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_NavEKF3: fix documentation derivation references
This commit is contained in:
parent
78d1ea4727
commit
8250fe4943
@ -22,7 +22,7 @@ extern const AP_HAL::HAL& hal;
|
|||||||
/*
|
/*
|
||||||
* Fuse true airspeed measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse true airspeed measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
*/
|
*/
|
||||||
void NavEKF3_core::FuseAirspeed()
|
void NavEKF3_core::FuseAirspeed()
|
||||||
{
|
{
|
||||||
@ -240,7 +240,7 @@ void NavEKF3_core::SelectBetaFusion()
|
|||||||
/*
|
/*
|
||||||
* Fuse sythetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse sythetic sideslip measurement of zero using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
*/
|
*/
|
||||||
void NavEKF3_core::FuseSideslip()
|
void NavEKF3_core::FuseSideslip()
|
||||||
{
|
{
|
||||||
|
@ -310,7 +310,7 @@ void NavEKF3_core::SelectMagFusion()
|
|||||||
/*
|
/*
|
||||||
* Fuse magnetometer measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse magnetometer measurements using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
*/
|
*/
|
||||||
void NavEKF3_core::FuseMagnetometer()
|
void NavEKF3_core::FuseMagnetometer()
|
||||||
{
|
{
|
||||||
@ -703,7 +703,7 @@ void NavEKF3_core::FuseMagnetometer()
|
|||||||
/*
|
/*
|
||||||
* Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse magnetic heading measurement using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
* This fusion method only modifies the orientation, does not require use of the magnetic field states and is computationally cheaper.
|
* This fusion method only modifies the orientation, does not require use of the magnetic field states and is computationally cheaper.
|
||||||
* It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground).
|
* It is suitable for use when the external magnetic field environment is disturbed (eg close to metal structures, on ground).
|
||||||
* It is not as robust to magnetometer failures.
|
* It is not as robust to magnetometer failures.
|
||||||
@ -930,7 +930,7 @@ void NavEKF3_core::fuseEulerYaw()
|
|||||||
/*
|
/*
|
||||||
* Fuse declination angle using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse declination angle using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
* This is used to prevent the declination of the EKF earth field states from drifting during operation without GPS
|
* This is used to prevent the declination of the EKF earth field states from drifting during operation without GPS
|
||||||
* or some other absolute position or velocity reference
|
* or some other absolute position or velocity reference
|
||||||
*/
|
*/
|
||||||
|
@ -260,7 +260,7 @@ void NavEKF3_core::EstimateTerrainOffset()
|
|||||||
/*
|
/*
|
||||||
* Fuse angular motion compensated optical flow rates using explicit algebraic equations generated with Matlab symbolic toolbox.
|
* Fuse angular motion compensated optical flow rates using explicit algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
* Requires a valid terrain height estimate.
|
* Requires a valid terrain height estimate.
|
||||||
*/
|
*/
|
||||||
void NavEKF3_core::FuseOptFlow()
|
void NavEKF3_core::FuseOptFlow()
|
||||||
|
@ -800,7 +800,7 @@ void NavEKF3_core::calcOutputStates()
|
|||||||
/*
|
/*
|
||||||
* Calculate the predicted state covariance matrix using algebraic equations generated with Matlab symbolic toolbox.
|
* Calculate the predicted state covariance matrix using algebraic equations generated with Matlab symbolic toolbox.
|
||||||
* The script file used to generate these and other equations in this filter can be found here:
|
* The script file used to generate these and other equations in this filter can be found here:
|
||||||
* https://github.com/priseborough/InertialNav/blob/master/derivations/RotationVectorAttitudeParameterisation/GenerateNavFilterEquations.m
|
* https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/GenerateNavFilterEquations.m
|
||||||
*/
|
*/
|
||||||
void NavEKF3_core::CovariancePrediction()
|
void NavEKF3_core::CovariancePrediction()
|
||||||
{
|
{
|
||||||
|
Loading…
Reference in New Issue
Block a user