Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
#include "AP_Math.h"
2
 
3
// a varient of asin() that checks the input ranges and ensures a
4
// valid angle as output. If nan is given as input then zero is
5
// returned.
6
float safe_asin(float v)
7
{
8
        if (isnan(v)) {
9
                return 0.0;
10
        }
11
        if (v >= 1.0) {
12
                return PI/2;
13
        }
14
        if (v <= -1.0) {
15
                return -PI/2;
16
        }
17
        return asin(v);
18
}
19
 
20
// a varient of sqrt() that checks the input ranges and ensures a
21
// valid value as output. If a negative number is given then 0 is
22
// returned. The reasoning is that a negative number for sqrt() in our
23
// code is usually caused by small numerical rounding errors, so the
24
// real input should have been zero
25
float safe_sqrt(float v)
26
{
27
        float ret = sqrt(v);
28
        if (isnan(ret)) {
29
                return 0;
30
        }
31
        return ret;
32
}
33
 
34
 
35
// find a rotation that is the combination of two other
36
// rotations. This is used to allow us to add an overall board
37
// rotation to an existing rotation of a sensor such as the compass
38
// Note that this relies the set of rotations being complete. The
39
// optional 'found' parameter is for the test suite to ensure that it is.
40
enum Rotation rotation_combination(enum Rotation r1, enum Rotation r2, bool *found)
41
{
42
        Vector3f tv1, tv2;
43
        enum Rotation r;
44
        tv1(1,2,3);
45
        tv1.rotate(r1);
46
        tv1.rotate(r2);
47
 
48
        for (r=ROTATION_NONE; r<ROTATION_MAX;
49
             r = (enum Rotation)((uint8_t)r+1)) {
50
                Vector3f diff;
51
                tv2(1,2,3);
52
                tv2.rotate(r);
53
                diff = tv1 - tv2;
54
                if (diff.length() < 1.0e-6) {
55
                        // we found a match
56
                        if (found) {
57
                                *found = true;
58
                        }
59
                        return r;
60
                }
61
        }
62
 
63
        // we found no matching rotation. Someone has edited the
64
        // rotations list and broken its completeness property ...
65
        if (found) {
66
                *found = false;
67
        }
68
        return ROTATION_NONE;
69
}