// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // test harness for vibration testing // #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #include #include #include #include #include #include const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; #define NUM_ACCELS 2 static int accel_fd[NUM_ACCELS]; static uint32_t total_samples[NUM_ACCELS]; static uint64_t last_accel_timestamp[NUM_ACCELS]; static DataFlash_File DataFlash("/fs/microsd/VIBTEST"); #define LOG_ACCEL0_MSG 215 struct PACKED log_Accel { LOG_PACKET_HEADER; uint32_t timestamp; float X, Y, Z; }; static const struct LogStructure log_structure[] PROGMEM = { LOG_COMMON_STRUCTURES, { LOG_ACCEL0_MSG, sizeof(log_Accel), "ACC0", "Ifff", "TimeUS,X,Y,Z" }, { LOG_ACCEL0_MSG+1, sizeof(log_Accel), "ACC1", "Ifff", "TimeUS,X,Y,Z" } }; void setup(void) { accel_fd[0] = open(ACCEL_DEVICE_PATH, O_RDONLY); accel_fd[1] = open(ACCEL_DEVICE_PATH "1", O_RDONLY); for (uint8_t i=0; iprintf("Failed to open accel[%u]\n", (unsigned)i); hal.scheduler->panic("Failed to open accel"); } // disable software filtering ioctl(accel_fd[i], ACCELIOCSLOWPASS, 0); // max queue depth ioctl(accel_fd[i], SENSORIOCSQUEUEDEPTH, 100); } DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0])); DataFlash.StartNewLog(); } void loop(void) { for (uint8_t i=0; iprintf("t=%lu total_samples=%lu/%lu\n", hal.scheduler->millis(), total_samples[0], total_samples[1]); } } } hal.scheduler->delay(1); } #else void setup() {} void loop() {} #endif // CONFIG_HAL_BOARD AP_HAL_MAIN();