mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
CPUInfo: added acos(), asin() and atan2()
This commit is contained in:
parent
9d7ed30023
commit
2861e235bb
@ -93,6 +93,9 @@ static void show_timings(void)
|
|||||||
TIMEIT("sin()", v_out = sin(v_f), 20);
|
TIMEIT("sin()", v_out = sin(v_f), 20);
|
||||||
TIMEIT("cos()", v_out = cos(v_f), 20);
|
TIMEIT("cos()", v_out = cos(v_f), 20);
|
||||||
TIMEIT("tan()", v_out = tan(v_f), 20);
|
TIMEIT("tan()", v_out = tan(v_f), 20);
|
||||||
|
TIMEIT("acos()", v_out = acos(v_f * 0.2), 20);
|
||||||
|
TIMEIT("asin()", v_out = asin(v_f * 0.2), 20);
|
||||||
|
TIMEIT("atan2()", v_out = atan2(v_f * 0.2, v_f * 0.3), 20);
|
||||||
TIMEIT("sqrt()",v_out = sqrt(v_f), 20);
|
TIMEIT("sqrt()",v_out = sqrt(v_f), 20);
|
||||||
|
|
||||||
TIMEIT("iadd8", v_out_8 += v_8, 100);
|
TIMEIT("iadd8", v_out_8 += v_8, 100);
|
||||||
|
@ -21,9 +21,12 @@ dadd 9.18 usec/call
|
|||||||
dsub 9.25 usec/call
|
dsub 9.25 usec/call
|
||||||
dmul 6.14 usec/call
|
dmul 6.14 usec/call
|
||||||
ddiv 6.07 usec/call
|
ddiv 6.07 usec/call
|
||||||
sin() 118.14 usec/call
|
sin() 112.35 usec/call
|
||||||
cos() 106.82 usec/call
|
cos() 113.11 usec/call
|
||||||
tan() 152.97 usec/call
|
tan() 154.92 usec/call
|
||||||
|
acos() 167.69 usec/call
|
||||||
|
asin() 82.16 usec/call
|
||||||
|
atan2() 193.34 usec/call
|
||||||
sqrt() 31.67 usec/call
|
sqrt() 31.67 usec/call
|
||||||
iadd8 0.48 usec/call
|
iadd8 0.48 usec/call
|
||||||
isub8 0.48 usec/call
|
isub8 0.48 usec/call
|
||||||
|
Loading…
Reference in New Issue
Block a user