mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: Fix typos
This commit is contained in:
parent
2802775e7d
commit
2bf9aa94ad
|
@ -169,7 +169,7 @@ AP_AHRS_DCM::reset(bool recover_eulers)
|
|||
// calculate initial roll angle
|
||||
roll = atan2f(-initAccVec.y, -initAccVec.z);
|
||||
} else {
|
||||
// If we cant use the accel vector, then align flat
|
||||
// If we can't use the accel vector, then align flat
|
||||
roll = 0.0f;
|
||||
pitch = 0.0f;
|
||||
}
|
||||
|
|
|
@ -941,7 +941,7 @@ void AP_AHRS_NavEKF::writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlo
|
|||
EKF2.writeOptFlowMeas(rawFlowQuality, rawFlowRates, rawGyroRates, msecFlowMeas);
|
||||
}
|
||||
|
||||
// inhibit GPS useage
|
||||
// inhibit GPS usage
|
||||
uint8_t AP_AHRS_NavEKF::setInhibitGPS(void)
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
|
|
|
@ -145,7 +145,7 @@ public:
|
|||
// write optical flow measurements to EKF
|
||||
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas);
|
||||
|
||||
// inibit GPS useage
|
||||
// inibit GPS usage
|
||||
uint8_t setInhibitGPS(void);
|
||||
|
||||
// get speed limit
|
||||
|
|
Loading…
Reference in New Issue