AP_Math: Fix typos

This commit is contained in:
Ricardo de Almeida Gonzaga 2016-05-12 14:02:03 -03:00 committed by Lucas De Marchi
parent 00b1915034
commit 481e3a2af6
5 changed files with 5 additions and 5 deletions

View File

@ -152,7 +152,7 @@ template float wrap_2PI<double>(const double radian);
template <class T>
T constrain_value(const T amt, const T low, const T high)
{
// the check for NaN as a float prevents propogation of floating point
// the check for NaN as a float prevents propagation of floating point
// errors through any function that uses constrain_float(). The normal
// float semantics already handle -Inf and +Inf
if (isnan(amt)) {

View File

@ -13,7 +13,7 @@
#include <inttypes.h>
/* CRC16 implementation acording to CCITT standards */
/* CRC16 implementation according to CCITT standards */
static const uint16_t crc16tab[256] = {
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,

View File

@ -235,7 +235,7 @@ void wgsecef2llh(const Vector3d &ecef, Vector3d &llh) {
return;
}
/* Caluclate some other constants as defined in the Fukushima paper. */
/* Calculate some other constants as defined in the Fukushima paper. */
const double P = p / WGS84_A;
const double e_c = sqrt(1. - WGS84_E*WGS84_E);
const double Z = fabs(ecef[2]) * e_c / WGS84_A;

View File

@ -207,7 +207,7 @@ bool mat_inverse(float* A, float* inv, uint8_t n)
memset(U_inv,0,n*n*sizeof(float));
mat_back_sub(U,U_inv,n);
// decomposed matrices no loger required
// decomposed matrices no longer required
free(L);
free(U);

View File

@ -42,7 +42,7 @@
* scalar triple product: a*(b%c) = c*(a%b) = b*(c%a)
* vector quadruple product: (a%b)*(c%d) = (a*c)*(b*d) - (a*d)*(b*c)
* if a is unit vector along b then a%b = -b%a = -b(cast to matrix)*a = 0
* vectors a1...an are linearly dependant if there exists a vector of scalars (b) where a1*b1 + ... + an*bn = 0
* vectors a1...an are linearly dependent if there exists a vector of scalars (b) where a1*b1 + ... + an*bn = 0
* or if the matrix (A) * b = 0
*
****************************************/