AP_NavEKF2: Fix documentation errors
This commit is contained in:
parent
54a431a51d
commit
b40016db62
@ -727,6 +727,7 @@ bool NavEKF::use_compass(void) const
|
||||
// rawGyroRates are the sensor rotation rates in rad/sec measured by the sensors internal gyro
|
||||
// The sign convention is that a RH physical rotation of the sensor about an axis produces both a positive flow and gyro rate
|
||||
// msecFlowMeas is the scheduler time in msec when the optical flow data was received from the sensor.
|
||||
// NOTE: AP_NavEKF does not use the posOffset data
|
||||
void NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, Vector3f &posOffset)
|
||||
{
|
||||
if (core) {
|
||||
|
@ -499,7 +499,6 @@ void NavEKF2_core::readGpsData()
|
||||
}
|
||||
|
||||
// convert GPS measurements to local NED and save to buffer to be fused later if we have a valid origin
|
||||
// correct for position offset of antenna in body frame
|
||||
if (validOrigin) {
|
||||
gpsDataNew.pos = location_diff(EKF_origin, gpsloc);
|
||||
gpsDataNew.hgt = 0.01f * (gpsloc.alt - EKF_origin.alt);
|
||||
|
Loading…
Reference in New Issue
Block a user