forked from Archive/PX4-Autopilot
Useful bits for high-rate logging
This commit is contained in:
parent
6dce57170e
commit
8c518aa237
|
@ -0,0 +1,88 @@
|
|||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script for logging purposes
|
||||
#
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm error
|
||||
fi
|
||||
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Start sensor drivers here.
|
||||
#
|
||||
|
||||
ms5611 start
|
||||
adc start
|
||||
|
||||
# mag might be external
|
||||
if hmc5883 start
|
||||
then
|
||||
echo "using HMC5883"
|
||||
fi
|
||||
|
||||
if mpu6000 start
|
||||
then
|
||||
echo "using MPU6000"
|
||||
fi
|
||||
|
||||
if l3gd20 start
|
||||
then
|
||||
echo "using L3GD20(H)"
|
||||
fi
|
||||
|
||||
if lsm303d start
|
||||
then
|
||||
set BOARD fmuv2
|
||||
else
|
||||
set BOARD fmuv1
|
||||
fi
|
||||
|
||||
# Start airspeed sensors
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "using MEAS airspeed sensor"
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
echo "using ETS airspeed sensor (bus 3)"
|
||||
else
|
||||
if ets_airspeed start -b 1
|
||||
then
|
||||
echo "Using ETS airspeed sensor (bus 1)"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start the sensor collection task.
|
||||
# IMPORTANT: this also loads param offsets
|
||||
# ALWAYS start this task before the
|
||||
# preflight_check.
|
||||
#
|
||||
if sensors start
|
||||
then
|
||||
echo "SENSORS STARTED"
|
||||
fi
|
||||
|
||||
sdlog2 start -r 250 -e -b 16
|
||||
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
|
@ -2,3 +2,11 @@
|
|||
#
|
||||
# PX4FMU startup script for test hackery.
|
||||
#
|
||||
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
|
||||
# Try to get an USB console
|
||||
nshterm /dev/ttyACM0 &
|
||||
fi
|
|
@ -0,0 +1,157 @@
|
|||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS, copy the px4iov2 firmware into
|
||||
# the ROMFS if it's available
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_logging
|
||||
ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v2_default.bin
|
||||
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/stm32/adc
|
||||
MODULES += drivers/stm32/tone_alarm
|
||||
MODULES += drivers/led
|
||||
MODULES += drivers/px4fmu
|
||||
MODULES += drivers/px4io
|
||||
MODULES += drivers/boards/px4fmu-v2
|
||||
MODULES += drivers/rgbled
|
||||
MODULES += drivers/mpu6000
|
||||
MODULES += drivers/lsm303d
|
||||
MODULES += drivers/l3gd20
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/mb12xx
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/hott/hott_telemetry
|
||||
MODULES += drivers/hott/hott_sensors
|
||||
MODULES += drivers/blinkm
|
||||
MODULES += drivers/roboclaw
|
||||
MODULES += drivers/airspeed
|
||||
MODULES += drivers/ets_airspeed
|
||||
MODULES += drivers/meas_airspeed
|
||||
MODULES += modules/sensors
|
||||
|
||||
# Needs to be burned to the ground and re-written; for now,
|
||||
# just don't build it.
|
||||
#MODULES += drivers/mkblctrl
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
MODULES += systemcmds/ramtron
|
||||
MODULES += systemcmds/bl_update
|
||||
MODULES += systemcmds/boardinfo
|
||||
MODULES += systemcmds/mixer
|
||||
MODULES += systemcmds/param
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/preflight_check
|
||||
MODULES += systemcmds/pwm
|
||||
MODULES += systemcmds/esc_calib
|
||||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
MODULES += systemcmds/nshterm
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
MODULES += modules/commander
|
||||
MODULES += modules/navigator
|
||||
MODULES += modules/mavlink
|
||||
MODULES += modules/mavlink_onboard
|
||||
|
||||
#
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/att_pos_estimator_ekf
|
||||
MODULES += modules/position_estimator_inav
|
||||
MODULES += examples/flow_position_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
#MODULES += modules/segway # XXX Needs GCC 4.7 fix
|
||||
MODULES += modules/fw_pos_control_l1
|
||||
MODULES += modules/fw_att_control
|
||||
MODULES += modules/multirotor_att_control
|
||||
MODULES += modules/multirotor_pos_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
MODULES += modules/sdlog2
|
||||
|
||||
#
|
||||
# Unit tests
|
||||
#
|
||||
#MODULES += modules/unit_test
|
||||
#MODULES += modules/commander/commander_tests
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/controllib
|
||||
MODULES += modules/uORB
|
||||
|
||||
#
|
||||
# Libraries
|
||||
#
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
MODULES += lib/mathlib
|
||||
MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/ecl
|
||||
MODULES += lib/external_lgpl
|
||||
MODULES += lib/geo
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# Demo apps
|
||||
#
|
||||
#MODULES += examples/math_demo
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky
|
||||
MODULES += examples/px4_simple_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/daemon
|
||||
#MODULES += examples/px4_daemon_app
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values
|
||||
#MODULES += examples/px4_mavlink_debug
|
||||
|
||||
# Tutorial code from
|
||||
# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
|
||||
#MODULES += examples/fixedwing_control
|
||||
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B
|
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef
|
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main )
|
|
@ -78,7 +78,8 @@ static int accel(int argc, char *argv[]);
|
|||
static int gyro(int argc, char *argv[]);
|
||||
static int mag(int argc, char *argv[]);
|
||||
static int baro(int argc, char *argv[]);
|
||||
static int mpu6k(int argc, char *argv[]);
|
||||
static int accel1(int argc, char *argv[]);
|
||||
static int gyro1(int argc, char *argv[]);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
|
@ -93,7 +94,8 @@ struct {
|
|||
{"gyro", "/dev/gyro", gyro},
|
||||
{"mag", "/dev/mag", mag},
|
||||
{"baro", "/dev/baro", baro},
|
||||
{"mpu6k", "/dev/mpu6k", mpu6k},
|
||||
{"accel1", "/dev/accel1", accel1},
|
||||
{"gyro1", "/dev/gyro1", gyro1},
|
||||
{NULL, NULL, NULL}
|
||||
};
|
||||
|
||||
|
@ -137,7 +139,7 @@ accel(int argc, char *argv[])
|
|||
}
|
||||
|
||||
if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
|
||||
warnx("MPU6K acceleration values out of range!");
|
||||
warnx("ACCEL1 acceleration values out of range!");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
|
@ -149,20 +151,19 @@ accel(int argc, char *argv[])
|
|||
}
|
||||
|
||||
static int
|
||||
mpu6k(int argc, char *argv[])
|
||||
accel1(int argc, char *argv[])
|
||||
{
|
||||
printf("\tMPU6K: test start\n");
|
||||
printf("\tACCEL1: test start\n");
|
||||
fflush(stdout);
|
||||
|
||||
int fd;
|
||||
struct accel_report buf;
|
||||
struct gyro_report gyro_buf;
|
||||
int ret;
|
||||
|
||||
fd = open("/dev/accel_mpu6k", O_RDONLY);
|
||||
fd = open("/dev/accel1", O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("\tMPU6K: open fail, run <mpu6000 start> first.\n");
|
||||
printf("\tACCEL1: open fail, run <mpu6000 start> or <lsm303d start> first.\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
|
@ -173,45 +174,21 @@ mpu6k(int argc, char *argv[])
|
|||
ret = read(fd, &buf, sizeof(buf));
|
||||
|
||||
if (ret != sizeof(buf)) {
|
||||
printf("\tMPU6K: read1 fail (%d)\n", ret);
|
||||
printf("\tACCEL1: read1 fail (%d)\n", ret);
|
||||
return ERROR;
|
||||
|
||||
} else {
|
||||
printf("\tMPU6K accel: x:%8.4f\ty:%8.4f\tz:%8.4f m/s^2\n", (double)buf.x, (double)buf.y, (double)buf.z);
|
||||
printf("\tACCEL1 accel: x:%8.4f\ty:%8.4f\tz:%8.4f m/s^2\n", (double)buf.x, (double)buf.y, (double)buf.z);
|
||||
}
|
||||
|
||||
if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
|
||||
warnx("MPU6K acceleration values out of range!");
|
||||
warnx("ACCEL1 acceleration values out of range!");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* Let user know everything is ok */
|
||||
printf("\tOK: MPU6K ACCEL passed all tests successfully\n");
|
||||
printf("\tOK: ACCEL1 passed all tests successfully\n");
|
||||
|
||||
close(fd);
|
||||
fd = open("/dev/gyro_mpu6k", O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("\tMPU6K GYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* wait at least 5 ms, sensor should have data after that */
|
||||
usleep(5000);
|
||||
|
||||
/* read data - expect samples */
|
||||
ret = read(fd, &gyro_buf, sizeof(gyro_buf));
|
||||
|
||||
if (ret != sizeof(gyro_buf)) {
|
||||
printf("\tMPU6K GYRO: read fail (%d)\n", ret);
|
||||
return ERROR;
|
||||
|
||||
} else {
|
||||
printf("\tMPU6K GYRO rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)gyro_buf.x, (double)gyro_buf.y, (double)gyro_buf.z);
|
||||
}
|
||||
|
||||
/* Let user know everything is ok */
|
||||
printf("\tOK: MPU6K GYRO passed all tests successfully\n");
|
||||
close(fd);
|
||||
|
||||
return OK;
|
||||
|
@ -255,6 +232,44 @@ gyro(int argc, char *argv[])
|
|||
return OK;
|
||||
}
|
||||
|
||||
static int
|
||||
gyro1(int argc, char *argv[])
|
||||
{
|
||||
printf("\tGYRO1: test start\n");
|
||||
fflush(stdout);
|
||||
|
||||
int fd;
|
||||
struct gyro_report buf;
|
||||
int ret;
|
||||
|
||||
fd = open("/dev/gyro1", O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("\tGYRO1: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/* wait at least 5 ms, sensor should have data after that */
|
||||
usleep(5000);
|
||||
|
||||
/* read data - expect samples */
|
||||
ret = read(fd, &buf, sizeof(buf));
|
||||
|
||||
if (ret != sizeof(buf)) {
|
||||
printf("\tGYRO1: read fail (%d)\n", ret);
|
||||
return ERROR;
|
||||
|
||||
} else {
|
||||
printf("\tGYRO1 rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z);
|
||||
}
|
||||
|
||||
/* Let user know everything is ok */
|
||||
printf("\tOK: GYRO1 passed all tests successfully\n");
|
||||
close(fd);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
static int
|
||||
mag(int argc, char *argv[])
|
||||
{
|
||||
|
|
Loading…
Reference in New Issue