From 11ff665ca00e61b49dbc6d8aa8ea9752cfe9dbe0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Dec 2011 18:52:00 +1100 Subject: [PATCH] CPUInfo: show the speed of 64 bit maths --- Tools/CPUInfo/CPUInfo.pde | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/CPUInfo/CPUInfo.pde b/Tools/CPUInfo/CPUInfo.pde index 4083ca57e1..37e6ae07fa 100644 --- a/Tools/CPUInfo/CPUInfo.pde +++ b/Tools/CPUInfo/CPUInfo.pde @@ -52,6 +52,8 @@ volatile uint16_t v_out_16 = 1; volatile uint8_t v_8 = 1; volatile uint8_t v_out_8 = 1; volatile uint8_t mbuf1[128], mbuf2[128]; +volatile uint64_t v_64 = 1; +volatile uint64_t v_out_64 = 1; static void show_timings(void) { @@ -107,6 +109,11 @@ static void show_timings(void) TIMEIT("imul32", v_out_32 *= v_32, 100); TIMEIT("idiv32", v_out_32 /= v_32, 100); + TIMEIT("iadd64", v_out_64 += v_64, 100); + TIMEIT("isub64", v_out_64 -= v_64, 100); + TIMEIT("imul64", v_out_64 *= v_64, 100); + TIMEIT("idiv64", v_out_64 /= v_64, 100); + TIMEIT("memcpy128", memcpy((void*)mbuf1, (const void *)mbuf2, sizeof(mbuf1)), 20); TIMEIT("memset128", memset((void*)mbuf1, 1, sizeof(mbuf1)), 20); TIMEIT("delay(1)", delay(1), 5);