APM:Libraries
VibTest.cpp
Go to the documentation of this file.
1 //
2 // test harness for vibration testing
3 //
4 
5 #include <stdarg.h>
6 #include <AP_Common/AP_Common.h>
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 #include <AP_Param/AP_Param.h>
10 #include <AP_ADC/AP_ADC.h>
12 #include <AP_Notify/AP_Notify.h>
13 #include <AP_GPS/AP_GPS.h>
14 #include <AP_Baro/AP_Baro.h>
15 #include <Filter/Filter.h>
16 #include <DataFlash/DataFlash.h>
18 #include <AP_Mission/AP_Mission.h>
20 #include <AP_Terrain/AP_Terrain.h>
21 #include <AP_AHRS/AP_AHRS.h>
23 #include <AP_Vehicle/AP_Vehicle.h>
24 #include <AP_Compass/AP_Compass.h>
27 #include <AP_Notify/AP_Notify.h>
30 
31 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
32 
33 #include <drivers/drv_accel.h>
34 #include <drivers/drv_hrt.h>
35 
36 #include <sys/types.h>
37 #include <sys/stat.h>
38 #include <fcntl.h>
39 #include <unistd.h>
40 #include <stdio.h>
41 
43 
53 static DataFlash_File DataFlash("/fs/microsd/VIBTEST");
54 
55 static const struct LogStructure log_structure[] = {
58 };
59 
60 void setup(void)
61 {
62  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
63  char accel_path[] = ACCEL_BASE_DEVICE_PATH "n";
64  char gyro_path[] = GYRO_BASE_DEVICE_PATH "n";
65  accel_path[strlen(accel_path)-1] = '0'+i;
66  gyro_path[strlen(gyro_path)-1] = '0'+i;
67  accel_fd[i] = open(accel_path, O_RDONLY|O_CLOEXEC);
68  gyro_fd[i] = open(gyro_path, O_RDONLY|O_CLOEXEC);
69  }
70  if (accel_fd[0] == -1 || gyro_fd[0] == -1) {
71  AP_HAL::panic("Failed to open accel/gyro 0");
72  }
73 
74  ioctl(gyro_fd[0], SENSORIOCSPOLLRATE, 1000);
75  ioctl(gyro_fd[0], GYROIOCSLOWPASS, 0);
76  ioctl(gyro_fd[0], GYROIOCSHWLOWPASS, 256);
77  ioctl(gyro_fd[0], GYROIOCSSAMPLERATE, 1000);
78  ioctl(gyro_fd[0], SENSORIOCSQUEUEDEPTH, 100);
79 
80  ioctl(gyro_fd[1], SENSORIOCSPOLLRATE, 800);
81  ioctl(gyro_fd[1], GYROIOCSLOWPASS, 0);
82  ioctl(gyro_fd[1], GYROIOCSHWLOWPASS, 100);
83  ioctl(gyro_fd[1], GYROIOCSSAMPLERATE, 800);
84  ioctl(gyro_fd[1], SENSORIOCSQUEUEDEPTH, 100);
85 
86  ioctl(accel_fd[0], SENSORIOCSPOLLRATE, 1000);
87  ioctl(accel_fd[0], ACCELIOCSLOWPASS, 0);
88  ioctl(accel_fd[0], ACCELIOCSRANGE, 16);
89  ioctl(accel_fd[0], ACCELIOCSHWLOWPASS, 256);
90  ioctl(accel_fd[0], ACCELIOCSSAMPLERATE, 1000);
91  ioctl(accel_fd[0], SENSORIOCSQUEUEDEPTH, 100);
92 
93  ioctl(accel_fd[1], SENSORIOCSPOLLRATE, 1600);
94  ioctl(accel_fd[1], ACCELIOCSLOWPASS, 0);
95  ioctl(accel_fd[1], ACCELIOCSRANGE, 16);
96  ioctl(accel_fd[1], ACCELIOCSHWLOWPASS, 194);
97  ioctl(accel_fd[1], ACCELIOCSSAMPLERATE, 1600);
98  ioctl(accel_fd[1], SENSORIOCSQUEUEDEPTH, 100);
99 
100  DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
101  DataFlash.StartNewLog();
102 }
103 
104 void loop(void)
105 {
106  bool got_sample = false;
107  static uint32_t last_print;
108  do {
109  got_sample = false;
110  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
111  struct accel_report accel_report;
112  struct gyro_report gyro_report;
113 
114  if (accel_fd[i] != -1 && ::read(accel_fd[i], &accel_report, sizeof(accel_report)) ==
115  sizeof(accel_report) &&
116  accel_report.timestamp != last_accel_timestamp[i]) {
117  uint32_t deltat = accel_report.timestamp - last_accel_timestamp[i];
118  if (deltat > accel_deltat_max[i]) {
119  accel_deltat_max[i] = deltat;
120  }
121  if (accel_deltat_min[i] == 0 || deltat < accel_deltat_max[i]) {
122  accel_deltat_min[i] = deltat;
123  }
124  last_accel_timestamp[i] = accel_report.timestamp;
125 
126  struct log_ACCEL pkt = {
127  LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ACC1_MSG+i)),
129  sample_us : accel_report.timestamp,
130  AccX : accel_report.x,
131  AccY : accel_report.y,
132  AccZ : accel_report.z
133  };
134  DataFlash.WriteBlock(&pkt, sizeof(pkt));
135  got_sample = true;
136  total_samples[i]++;
137  }
138  if (gyro_fd[i] != -1 && ::read(gyro_fd[i], &gyro_report, sizeof(gyro_report)) ==
139  sizeof(gyro_report) &&
140  gyro_report.timestamp != last_gyro_timestamp[i]) {
141  uint32_t deltat = gyro_report.timestamp - last_gyro_timestamp[i];
142  if (deltat > gyro_deltat_max[i]) {
143  gyro_deltat_max[i] = deltat;
144  }
145  if (gyro_deltat_min[i] == 0 || deltat < gyro_deltat_max[i]) {
146  gyro_deltat_min[i] = deltat;
147  }
148  last_gyro_timestamp[i] = gyro_report.timestamp;
149 
150  struct log_GYRO pkt = {
151  LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GYR1_MSG+i)),
153  sample_us : gyro_report.timestamp,
154  GyrX : gyro_report.x,
155  GyrY : gyro_report.y,
156  GyrZ : gyro_report.z
157  };
158  DataFlash.WriteBlock(&pkt, sizeof(pkt));
159  got_sample = true;
160  total_samples[i]++;
161  }
162  }
163  if (got_sample) {
164  if (total_samples[0] % 2000 == 0 && last_print != total_samples[0]) {
165  last_print = total_samples[0];
166  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",
167  (unsigned long)AP_HAL::millis(),
168  (unsigned long)total_samples[0],
169  (unsigned long)total_samples[1],
170  (unsigned long)total_samples[2],
171  accel_deltat_min[0],
172  accel_deltat_max[0],
173  accel_deltat_min[1],
174  accel_deltat_max[1],
179 #if 0
180  ::printf("t=%lu total_samples=%lu/%lu/%lu adt=%u:%u/%u:%u/%u:%u gdt=%u:%u/%u:%u/%u:%u\n",
181  AP_HAL::millis(),
182  total_samples[0], total_samples[1],total_samples[2],
189 #endif
190 
191  memset(accel_deltat_min, 0, sizeof(accel_deltat_min));
192  memset(accel_deltat_max, 0, sizeof(accel_deltat_max));
193  memset(gyro_deltat_min, 0, sizeof(gyro_deltat_min));
194  memset(gyro_deltat_max, 0, sizeof(gyro_deltat_max));
195  }
196  }
197  } while (got_sample);
198  hal.scheduler->delay_microseconds(100);
199 }
200 
201 #else
202 const AP_HAL::HAL& hal = AP_HAL::get_HAL();
203 void setup() {}
204 void loop() {}
205 #endif // CONFIG_HAL_BOARD
206 
207 AP_HAL_MAIN();
int printf(const char *fmt,...)
Definition: stdio.c:113
void setup(void)
Definition: VibTest.cpp:60
float GyrZ
Definition: LogStructure.h:863
uint64_t sample_us
Definition: LogStructure.h:855
uint64_t time_us
Definition: LogStructure.h:861
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
AP_HAL::UARTDriver * console
Definition: HAL.h:110
static const struct LogStructure log_structure[]
Definition: VibTest.cpp:55
float GyrX
Definition: LogStructure.h:863
float AccY
Definition: LogStructure.h:856
static int accel_fd[INS_MAX_INSTANCES]
Definition: VibTest.cpp:44
static DataFlash_File DataFlash("/fs/microsd/VIBTEST")
#define LOG_COMMON_STRUCTURES
static uint32_t gyro_deltat_min[INS_MAX_INSTANCES]
Definition: VibTest.cpp:51
float AccX
Definition: LogStructure.h:856
float GyrY
Definition: LogStructure.h:863
static uint64_t last_accel_timestamp[INS_MAX_INSTANCES]
Definition: VibTest.cpp:47
uint64_t time_us
Definition: LogStructure.h:854
#define LOG_EXTRA_STRUCTURES
A system for managing and storing variables that are of general interest to the system.
static uint32_t total_samples[INS_MAX_INSTANCES]
Definition: VibTest.cpp:46
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
uint64_t sample_us
Definition: LogStructure.h:862
uint32_t millis()
Definition: system.cpp:157
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
uint64_t micros64()
Definition: system.cpp:162
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
static int gyro_fd[INS_MAX_INSTANCES]
Definition: VibTest.cpp:45
const HAL & get_HAL()
static uint32_t accel_deltat_min[INS_MAX_INSTANCES]
Definition: VibTest.cpp:49
Common definitions and utility routines for the ArduPilot libraries.
static uint64_t last_gyro_timestamp[INS_MAX_INSTANCES]
Definition: VibTest.cpp:48
void loop(void)
Definition: VibTest.cpp:104
static uint32_t accel_deltat_max[INS_MAX_INSTANCES]
Definition: VibTest.cpp:50
float AccZ
Definition: LogStructure.h:856
virtual void delay_microseconds(uint16_t us)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
Catch-all header that defines all supported RangeFinder classes.
#define INS_MAX_INSTANCES
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
AP_HAL_MAIN()
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: VibTest.cpp:42
static uint32_t gyro_deltat_max[INS_MAX_INSTANCES]
Definition: VibTest.cpp:52