31 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 33 #include <drivers/drv_accel.h> 34 #include <drivers/drv_hrt.h> 36 #include <sys/types.h> 53 static DataFlash_File
DataFlash(
"/fs/microsd/VIBTEST");
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;
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);
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);
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);
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);
106 bool got_sample =
false;
107 static uint32_t last_print;
111 struct accel_report accel_report;
112 struct gyro_report gyro_report;
115 sizeof(accel_report) &&
130 AccX : accel_report.x,
131 AccY : accel_report.y,
132 AccZ : accel_report.z
139 sizeof(gyro_report) &&
154 GyrX : gyro_report.x,
155 GyrY : gyro_report.y,
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",
169 (
unsigned long)total_samples[1],
170 (
unsigned long)total_samples[2],
180 ::printf(
"t=%lu total_samples=%lu/%lu/%lu adt=%u:%u/%u:%u/%u:%u gdt=%u:%u/%u:%u/%u:%u\n",
182 total_samples[0], total_samples[1],total_samples[2],
197 }
while (got_sample);
205 #endif // CONFIG_HAL_BOARD
int printf(const char *fmt,...)
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
AP_HAL::UARTDriver * console
static const struct LogStructure log_structure[]
static int accel_fd[INS_MAX_INSTANCES]
static DataFlash_File DataFlash("/fs/microsd/VIBTEST")
#define LOG_COMMON_STRUCTURES
static uint32_t gyro_deltat_min[INS_MAX_INSTANCES]
static uint64_t last_accel_timestamp[INS_MAX_INSTANCES]
#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]
virtual void printf(const char *,...) FMT_PRINTF(2
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
static int gyro_fd[INS_MAX_INSTANCES]
static uint32_t accel_deltat_min[INS_MAX_INSTANCES]
Common definitions and utility routines for the ArduPilot libraries.
static uint64_t last_gyro_timestamp[INS_MAX_INSTANCES]
static uint32_t accel_deltat_max[INS_MAX_INSTANCES]
virtual void delay_microseconds(uint16_t us)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Catch-all header that defines all supported RangeFinder classes.
#define INS_MAX_INSTANCES
#define LOG_PACKET_HEADER_INIT(id)
AP_HAL::Scheduler * scheduler
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static uint32_t gyro_deltat_max[INS_MAX_INSTANCES]