2014-05-14 02:56:45 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
|
|
|
|
//
|
|
|
|
// test harness for vibration testing
|
|
|
|
//
|
|
|
|
|
|
|
|
#include <stdarg.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AP_ADC/AP_ADC.h>
|
|
|
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
|
|
|
#include <AP_Notify/AP_Notify.h>
|
|
|
|
#include <AP_GPS/AP_GPS.h>
|
|
|
|
#include <AP_Baro/AP_Baro.h>
|
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <DataFlash/DataFlash.h>
|
|
|
|
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
|
|
#include <AP_Mission/AP_Mission.h>
|
|
|
|
#include <StorageManager/StorageManager.h>
|
|
|
|
#include <AP_Terrain/AP_Terrain.h>
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_Airspeed/AP_Airspeed.h>
|
|
|
|
#include <AP_Vehicle/AP_Vehicle.h>
|
|
|
|
#include <AP_Compass/AP_Compass.h>
|
|
|
|
#include <AP_Scheduler/AP_Scheduler.h>
|
|
|
|
#include <AP_Declination/AP_Declination.h>
|
|
|
|
#include <AP_Notify/AP_Notify.h>
|
|
|
|
#include <AP_NavEKF/AP_NavEKF.h>
|
|
|
|
#include <AP_BattMonitor/AP_BattMonitor.h>
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
|
|
|
#include <AP_Rally/AP_Rally.h>
|
2015-05-06 21:51:52 -03:00
|
|
|
|
2014-05-16 08:23:49 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
2014-05-14 02:56:45 -03:00
|
|
|
|
|
|
|
#include <drivers/drv_accel.h>
|
|
|
|
#include <drivers/drv_hrt.h>
|
|
|
|
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <unistd.h>
|
2014-07-30 23:48:19 -03:00
|
|
|
#include <stdio.h>
|
2014-05-14 02:56:45 -03:00
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2014-05-14 02:56:45 -03:00
|
|
|
|
2014-07-07 21:07:58 -03:00
|
|
|
static int accel_fd[INS_MAX_INSTANCES];
|
|
|
|
static int gyro_fd[INS_MAX_INSTANCES];
|
|
|
|
static uint32_t total_samples[INS_MAX_INSTANCES];
|
|
|
|
static uint64_t last_accel_timestamp[INS_MAX_INSTANCES];
|
|
|
|
static uint64_t last_gyro_timestamp[INS_MAX_INSTANCES];
|
2014-07-08 23:12:23 -03:00
|
|
|
static uint32_t accel_deltat_min[INS_MAX_INSTANCES];
|
|
|
|
static uint32_t accel_deltat_max[INS_MAX_INSTANCES];
|
|
|
|
static uint32_t gyro_deltat_min[INS_MAX_INSTANCES];
|
|
|
|
static uint32_t gyro_deltat_max[INS_MAX_INSTANCES];
|
2014-05-14 02:56:45 -03:00
|
|
|
static DataFlash_File DataFlash("/fs/microsd/VIBTEST");
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
static const struct LogStructure log_structure[] = {
|
2014-05-14 02:56:45 -03:00
|
|
|
LOG_COMMON_STRUCTURES,
|
2015-05-07 00:25:37 -03:00
|
|
|
LOG_EXTRA_STRUCTURES
|
2014-05-14 02:56:45 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
void setup(void)
|
|
|
|
{
|
2014-07-07 21:07:58 -03:00
|
|
|
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
|
2015-05-06 21:51:52 -03:00
|
|
|
char accel_path[] = ACCEL_BASE_DEVICE_PATH "n";
|
|
|
|
char gyro_path[] = GYRO_BASE_DEVICE_PATH "n";
|
|
|
|
accel_path[strlen(accel_path)-1] = '0'+i;
|
|
|
|
gyro_path[strlen(gyro_path)-1] = '0'+i;
|
2014-07-07 21:07:58 -03:00
|
|
|
accel_fd[i] = open(accel_path, O_RDONLY);
|
|
|
|
gyro_fd[i] = open(gyro_path, O_RDONLY);
|
|
|
|
}
|
2014-07-08 19:11:52 -03:00
|
|
|
if (accel_fd[0] == -1 || gyro_fd[0] == -1) {
|
2015-11-19 23:11:52 -04:00
|
|
|
AP_HAL::panic("Failed to open accel/gyro 0");
|
2014-07-07 21:07:58 -03:00
|
|
|
}
|
2014-05-14 02:56:45 -03:00
|
|
|
|
2015-05-06 21:51:52 -03:00
|
|
|
ioctl(gyro_fd[0], SENSORIOCSPOLLRATE, 1000);
|
|
|
|
ioctl(gyro_fd[0], GYROIOCSLOWPASS, 0);
|
|
|
|
ioctl(gyro_fd[0], GYROIOCSHWLOWPASS, 256);
|
|
|
|
ioctl(gyro_fd[0], GYROIOCSSAMPLERATE, 1000);
|
|
|
|
ioctl(gyro_fd[0], SENSORIOCSQUEUEDEPTH, 100);
|
|
|
|
|
|
|
|
ioctl(gyro_fd[1], SENSORIOCSPOLLRATE, 800);
|
|
|
|
ioctl(gyro_fd[1], GYROIOCSLOWPASS, 0);
|
|
|
|
ioctl(gyro_fd[1], GYROIOCSHWLOWPASS, 100);
|
|
|
|
ioctl(gyro_fd[1], GYROIOCSSAMPLERATE, 800);
|
|
|
|
ioctl(gyro_fd[1], SENSORIOCSQUEUEDEPTH, 100);
|
|
|
|
|
|
|
|
ioctl(accel_fd[0], SENSORIOCSPOLLRATE, 1000);
|
|
|
|
ioctl(accel_fd[0], ACCELIOCSLOWPASS, 0);
|
|
|
|
ioctl(accel_fd[0], ACCELIOCSRANGE, 16);
|
|
|
|
ioctl(accel_fd[0], ACCELIOCSHWLOWPASS, 256);
|
|
|
|
ioctl(accel_fd[0], ACCELIOCSSAMPLERATE, 1000);
|
|
|
|
ioctl(accel_fd[0], SENSORIOCSQUEUEDEPTH, 100);
|
|
|
|
|
|
|
|
ioctl(accel_fd[1], SENSORIOCSPOLLRATE, 1600);
|
|
|
|
ioctl(accel_fd[1], ACCELIOCSLOWPASS, 0);
|
|
|
|
ioctl(accel_fd[1], ACCELIOCSRANGE, 16);
|
|
|
|
ioctl(accel_fd[1], ACCELIOCSHWLOWPASS, 194);
|
|
|
|
ioctl(accel_fd[1], ACCELIOCSSAMPLERATE, 1600);
|
|
|
|
ioctl(accel_fd[1], SENSORIOCSQUEUEDEPTH, 100);
|
2014-05-14 02:56:45 -03:00
|
|
|
|
2015-07-20 16:53:47 -03:00
|
|
|
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
|
2014-05-14 02:56:45 -03:00
|
|
|
DataFlash.StartNewLog();
|
|
|
|
}
|
|
|
|
|
|
|
|
void loop(void)
|
|
|
|
{
|
2014-07-07 21:07:58 -03:00
|
|
|
bool got_sample = false;
|
2014-07-08 23:12:23 -03:00
|
|
|
static uint32_t last_print;
|
2014-07-07 21:07:58 -03:00
|
|
|
do {
|
|
|
|
got_sample = false;
|
|
|
|
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
|
|
|
|
struct accel_report accel_report;
|
|
|
|
struct gyro_report gyro_report;
|
|
|
|
|
|
|
|
if (accel_fd[i] != -1 && ::read(accel_fd[i], &accel_report, sizeof(accel_report)) ==
|
|
|
|
sizeof(accel_report) &&
|
|
|
|
accel_report.timestamp != last_accel_timestamp[i]) {
|
2014-07-08 23:12:23 -03:00
|
|
|
uint32_t deltat = accel_report.timestamp - last_accel_timestamp[i];
|
|
|
|
if (deltat > accel_deltat_max[i]) {
|
|
|
|
accel_deltat_max[i] = deltat;
|
|
|
|
}
|
|
|
|
if (accel_deltat_min[i] == 0 || deltat < accel_deltat_max[i]) {
|
|
|
|
accel_deltat_min[i] = deltat;
|
|
|
|
}
|
2014-07-07 21:07:58 -03:00
|
|
|
last_accel_timestamp[i] = accel_report.timestamp;
|
|
|
|
|
|
|
|
struct log_ACCEL pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+i)),
|
2015-11-19 23:11:52 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2015-06-17 01:15:58 -03:00
|
|
|
sample_us : accel_report.timestamp,
|
2014-07-07 21:07:58 -03:00
|
|
|
AccX : accel_report.x,
|
|
|
|
AccY : accel_report.y,
|
|
|
|
AccZ : accel_report.z
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
got_sample = true;
|
2014-07-07 21:23:56 -03:00
|
|
|
total_samples[i]++;
|
2014-07-07 21:07:58 -03:00
|
|
|
}
|
|
|
|
if (gyro_fd[i] != -1 && ::read(gyro_fd[i], &gyro_report, sizeof(gyro_report)) ==
|
|
|
|
sizeof(gyro_report) &&
|
|
|
|
gyro_report.timestamp != last_gyro_timestamp[i]) {
|
2014-07-08 23:12:23 -03:00
|
|
|
uint32_t deltat = gyro_report.timestamp - last_gyro_timestamp[i];
|
|
|
|
if (deltat > gyro_deltat_max[i]) {
|
|
|
|
gyro_deltat_max[i] = deltat;
|
|
|
|
}
|
|
|
|
if (gyro_deltat_min[i] == 0 || deltat < gyro_deltat_max[i]) {
|
|
|
|
gyro_deltat_min[i] = deltat;
|
|
|
|
}
|
2014-07-07 21:07:58 -03:00
|
|
|
last_gyro_timestamp[i] = gyro_report.timestamp;
|
|
|
|
|
|
|
|
struct log_GYRO pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
|
2015-11-19 23:11:52 -04:00
|
|
|
time_us : AP_HAL::micros64(),
|
2015-06-17 01:15:58 -03:00
|
|
|
sample_us : gyro_report.timestamp,
|
2014-07-07 21:07:58 -03:00
|
|
|
GyrX : gyro_report.x,
|
|
|
|
GyrY : gyro_report.y,
|
|
|
|
GyrZ : gyro_report.z
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
got_sample = true;
|
|
|
|
total_samples[i]++;
|
2014-07-07 21:23:56 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
if (got_sample) {
|
2014-07-08 23:12:23 -03:00
|
|
|
if (total_samples[0] % 2000 == 0 && last_print != total_samples[0]) {
|
|
|
|
last_print = total_samples[0];
|
|
|
|
hal.console->printf("t=%lu total_samples=%lu/%lu/%lu adt=%u:%u/%u:%u/%u:%u gdt=%u:%u/%u:%u/%u:%u\n",
|
2015-11-19 23:11:52 -04:00
|
|
|
(unsigned long)AP_HAL::millis(),
|
2015-05-06 21:51:52 -03:00
|
|
|
(unsigned long)total_samples[0],
|
|
|
|
(unsigned long)total_samples[1],
|
|
|
|
(unsigned long)total_samples[2],
|
|
|
|
accel_deltat_min[0],
|
|
|
|
accel_deltat_max[0],
|
|
|
|
accel_deltat_min[1],
|
|
|
|
accel_deltat_max[1],
|
2014-07-08 23:12:23 -03:00
|
|
|
accel_deltat_min[2], accel_deltat_max[2],
|
|
|
|
gyro_deltat_min[0], gyro_deltat_max[0],
|
|
|
|
gyro_deltat_min[1], gyro_deltat_max[1],
|
|
|
|
gyro_deltat_min[2], gyro_deltat_max[2]);
|
2014-07-30 23:48:19 -03:00
|
|
|
#if 0
|
|
|
|
::printf("t=%lu total_samples=%lu/%lu/%lu adt=%u:%u/%u:%u/%u:%u gdt=%u:%u/%u:%u/%u:%u\n",
|
2015-11-19 23:11:52 -04:00
|
|
|
AP_HAL::millis(),
|
2014-07-30 23:48:19 -03:00
|
|
|
total_samples[0], total_samples[1],total_samples[2],
|
|
|
|
accel_deltat_min[0], accel_deltat_max[0],
|
|
|
|
accel_deltat_min[1], accel_deltat_max[1],
|
|
|
|
accel_deltat_min[2], accel_deltat_max[2],
|
|
|
|
gyro_deltat_min[0], gyro_deltat_max[0],
|
|
|
|
gyro_deltat_min[1], gyro_deltat_max[1],
|
|
|
|
gyro_deltat_min[2], gyro_deltat_max[2]);
|
|
|
|
#endif
|
2014-07-08 23:12:23 -03:00
|
|
|
|
|
|
|
memset(accel_deltat_min, 0, sizeof(accel_deltat_min));
|
|
|
|
memset(accel_deltat_max, 0, sizeof(accel_deltat_max));
|
|
|
|
memset(gyro_deltat_min, 0, sizeof(gyro_deltat_min));
|
|
|
|
memset(gyro_deltat_max, 0, sizeof(gyro_deltat_max));
|
2014-05-14 02:56:45 -03:00
|
|
|
}
|
|
|
|
}
|
2014-07-07 21:07:58 -03:00
|
|
|
} while (got_sample);
|
2015-05-06 21:51:52 -03:00
|
|
|
hal.scheduler->delay_microseconds(100);
|
2014-05-14 02:56:45 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
#else
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2014-05-14 02:56:45 -03:00
|
|
|
void setup() {}
|
|
|
|
void loop() {}
|
|
|
|
#endif // CONFIG_HAL_BOARD
|
|
|
|
|
|
|
|
AP_HAL_MAIN();
|