StorageTest.cpp 2.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102
  1. //
  2. // Simple test for the StorageManager class
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <StorageManager/StorageManager.h>
  6. void setup();
  7. void loop();
  8. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  9. #define DO_INITIALISATION 1
  10. /*
  11. instantiate all 4 storage types
  12. */
  13. static StorageAccess all_storage[4] = {
  14. StorageAccess(StorageManager::StorageParam),
  15. StorageAccess(StorageManager::StorageMission),
  16. StorageAccess(StorageManager::StorageFence),
  17. StorageAccess(StorageManager::StorageRally)
  18. };
  19. /*
  20. simple random generator, see http://en.wikipedia.org/wiki/Random_number_generation
  21. */
  22. static uint16_t get_random(void)
  23. {
  24. static uint32_t m_z = 1234;
  25. static uint32_t m_w = 76542;
  26. m_z = 36969 * (m_z & 65535) + (m_z >> 16);
  27. m_w = 18000 * (m_w & 65535) + (m_w >> 16);
  28. return ((m_z << 16) + m_w) & 0xFFFF;
  29. }
  30. /*
  31. return a predictable value for an offset
  32. */
  33. static uint8_t pvalue(uint16_t offset)
  34. {
  35. return ((offset * 7) + 13) % 65536;
  36. }
  37. void setup(void)
  38. {
  39. hal.console->printf("StorageTest startup...\n");
  40. #if DO_INITIALISATION
  41. for (uint8_t type = 0; type < 4; type++) {
  42. const StorageAccess &storage = all_storage[type];
  43. hal.console->printf("Init type %u\n", (unsigned)type);
  44. for (uint16_t i = 0; i < storage.size(); i++) {
  45. storage.write_byte(i, pvalue(i));
  46. }
  47. }
  48. #endif
  49. }
  50. void loop(void)
  51. {
  52. static uint32_t count;
  53. uint8_t type = get_random() % 4;
  54. const StorageAccess &storage = all_storage[type];
  55. uint16_t offset = get_random() % storage.size();
  56. uint8_t length = (get_random() & 31);
  57. if (offset + length > storage.size()) {
  58. length = storage.size() - offset;
  59. }
  60. if (length == 0) {
  61. return;
  62. }
  63. uint8_t b[length];
  64. for (uint8_t i=0; i<length; i++) {
  65. b[i] = pvalue(offset+i);
  66. }
  67. if (get_random() % 2 == 1) {
  68. if (!storage.write_block(offset, b, length)) {
  69. hal.console->printf("write failed at offset %u length %u\n",
  70. (unsigned)offset, (unsigned)length);
  71. }
  72. } else {
  73. uint8_t b2[length];
  74. if (!storage.read_block(b2, offset, length)) {
  75. hal.console->printf("read failed at offset %u length %u\n",
  76. (unsigned)offset, (unsigned)length);
  77. }
  78. if (memcmp(b, b2, length) != 0) {
  79. hal.console->printf("bad data at offset %u length %u\n",
  80. (unsigned)offset, (unsigned)length);
  81. }
  82. }
  83. count++;
  84. if (count % 10000 == 0) {
  85. hal.console->printf("%u ops\n", (unsigned)count);
  86. }
  87. }
  88. AP_HAL_MAIN();