Hi,
For an experiment, I want to use my Pixhawk as datalogger ONLY.
I want know the vibration during flight.
I think the best would be to log the acceleration and giro data as good as possible (high resolution). The CPU should just concentrate on logging the data for about 3 minutes on the SD card.
I’m not so familiar with the firmware but able to do some changes to it.
Maybe somebody would like to give me some advice how I can change the Pixhawk to a high resolution IMU data logger?
I also think the SD card might not be as fast. So I don’t know if it would make sense to use the internal storage as buffer?
Thank you very much.
set
SDLOG_PRIO_BOOST = 3
EKF2_REC_RPL = 1
And you will have the IMU data logged at 500 Hz
More info here
http://dev.px4.io/ekf2_log_replay.html
Thank you very much for your answer.
This will log the raw unfiltered IMU data, right?
What about the user-selectable filters inside the IMU itself (DLPF_CFG register) ? Is it possible to influence/change/deactivate those programmable filters?
I think if you really want to know 100% what’s happening to the sensor data you will have to dig for it in the drivers.
The highest frequency at which you can get IMU data on the Pixhawk is 1000Hz I think (not sure if you could go higher). I think some of the data is down-sampled and possibly filtered in the drivers (using a digital low pass filter). Some of the data I also assume is integrated and represented as delta angles / delta velocities with corresponding delta time.
So if you want to do analysis then I would suggest to look at the data sheet of the corresponding IMU and the drivers in PX4.
The experts on this topic are probably @LorenzMeier and @JulianOes
I just checked out the datasheet of the MPU6000 and for the gyroscope, the output data rate is 8000 Hz and for the accelerometer 1000 Hz.
Would be awesome if I could somehow log the data within the full resolution of the gyro/accelerometer.
Any ideas and help is welcome. Thank you.
Actually, how is the log triggered?
As soon as the “SWITCH” is turned on? Won’t this log all available data? Because I just want IMU data logged on the SD…
tumbili
November 10, 2016, 6:25am
7
@michael_wintergarden I think logging starts when the vehicle is armed. The IMU data is logged but depending on what you want to do with the data you might want to know what kind of downsampling and filtering was done to it.
But how can I arm the pixhawk continuously? I can’t really use an extra remote control for that…
You will have to remove the -a from the startup script
#!/bin/sh
# Un comment and use set +e to ignore and set -e to enable 'exit on error control'
set +e
# Un comment the line below to help debug scripts by printing a trace of the script commands
#set -x
# PX4FMU startup script.
#
# NOTE: environment variable references:
# If the dollar sign ('$') is followed by a left bracket ('{') then the
# variable name is terminated with the right bracket character ('}').
# Otherwise, the variable name goes to the end of the argument.
#
#
# NOTE: COMMENT LINES ARE REMOVED BEFORE STORED IN ROMFS.
#
#------------------------------------------------------------------------------
#
# Set default paramter values.
# Do not add intra word spaces
# it wastes flash
#
set AUX_MODE pwm
set DATAMAN_OPT ""
set FAILSAFE none
set FAILSAFE_AUX none
set FCONFIG /fs/microsd/etc/config.txt
set FEXTRAS /fs/microsd/etc/extras.txt
set FMU_ARGS ""
set FMU_MODE pwm
set FRC /fs/microsd/etc/rc.txt
set IO_PRESENT no
set IOFW "/etc/extras/px4_io-v2_default.bin"
set IO_PRESENT no
set LOG_FILE /fs/microsd/bootlog.txt
set LOGGER_ARGS ""
set LOGGER_BUF 14
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
set MK_MODE none
set MKBLCTRL_ARG ""
set OUTPUT_MODE none
set PARAM_FILE /fs/microsd/params
set PWM_AUX_DISARMED p:PWM_AUX_DISARMED
set PWM_AUX_MAX p:PWM_AUX_MAX
set PWM_AUX_MIN p:PWM_AUX_MIN
set PWM_AUX_OUT none
set PWM_AUX_RATE p:PWM_AUX_RATE
set PWM_DISARMED p:PWM_DISARMED
set PWM_MAX p:PWM_MAX
set PWM_MIN p:PWM_MIN
set PWM_OUT none
set PWM_RATE p:PWM_RATE
set SDCARD_MIXERS_PATH /fs/microsd/etc/mixers
set USE_IO no
set VEHICLE_TYPE none
# Airframe parameter versioning: airframe maintainers can set this in the
# airframe startup script, and then increase it by one whenever an airframe
# parameter is updated - it will ensure that these parameters will be updated
# when the firmware is flashed.
set PARAM_DEFAULTS_VER 1
#
# Mount the procfs.
#
mount -t procfs /proc
#
# Start CDC/ACM serial driver.
#
sercon
#
# Print full system version.
#
ver all
#
# Start the ORB (first app to start)
# tone_alarm and tune_control
# is dependent.
#
uorb start
#
# Try to mount the microSD card.
#
# REBOOTWORK this needs to start after the flight control loop.
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
if hardfault_log check
then
# Error tune.
tune_control play -t 2
if hardfault_log commit
then
hardfault_log reset
fi
else
# Play the startup tune.
tune_control play -t 1
fi
else
# tune SD_INIT
tune_control play -t 16
if mkfatfs /dev/mmcsd0
then
if mount -t vfat /dev/mmcsd0 /fs/microsd
then
echo "INFO [init] card formatted"
else
tune_control play -t 17
echo "ERROR [init] format failed"
set LOG_FILE /dev/null
fi
else
set LOG_FILE /dev/null
fi
fi
# AEROCORE2 shouldn't have an sd card and CF2 may optionally have an sd card.
if ! ver hwcmp BITCRAZE_CRAZYFLIE GUMSTIX_AEROCORE2
then
# Run no SD alarm.
if [ $LOG_FILE = /dev/null ]
then
# tune Make FS MBAGP
tune_control play -t 2
fi
fi
#
# Look for an init script on the microSD card.
# Disable autostart if the script found.
#
if [ -f $FRC ]
then
sh $FRC
else
#
# Set the parameter file if mtd starts successfully.
#
if mtd start
then
set PARAM_FILE /fs/mtd_params
fi
#
# Load parameters.
#
param select $PARAM_FILE
if ! param load
then
param reset
fi
#
# Set AUTOCNF flag to use it in AUTOSTART scripts.
#
if param compare SYS_AUTOCONFIG 1
then
# Wipe out params except RC*, flight modes, total flight time, accel cal, gyro cal
param reset_nostart RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO*
set AUTOCNF yes
else
if param compare SYS_AUTOCONFIG 2
then
set AUTOCNF yes
else
set AUTOCNF no
fi
fi
#
# Optional board defaults: rc.board_defaults
#
set BOARD_RC_DEFAULTS /etc/init.d/rc.board_defaults
if [ -f $BOARD_RC_DEFAULTS ]
then
echo "Board defaults: ${BOARD_RC_DEFAULTS}"
sh $BOARD_RC_DEFAULTS
fi
unset BOARD_RC_DEFAULTS
#
# Waypoint storage.
# REBOOTWORK this needs to start in parallel.
#
dataman start $DATAMAN_OPT
#
# Start the socket communication send_event handler.
#
send_event start
#
# Start the resource load monitor.
#
load_mon start
#
# Start system state indicator.
#
rgbled start
rgbled_ncp5623c start
rgbled_pwm start
if blinkm start
then
blinkm systemstate
fi
#
# Start the tone_alarm driver.
# Needs to be started after the parameters are loaded (for CBRK_BUZZER).
# Note that this will still play the already published startup tone.
#
tone_alarm start
if param compare SYS_FMU_TASK 1
then
set FMU_ARGS "-t"
fi
#
# Set parameters and env variables for selected AUTOSTART.
#
if ! param compare SYS_AUTOSTART 0
then
sh /etc/init.d/rc.autostart
fi
#
# Override parameters from user configuration file.
#
if [ -f $FCONFIG ]
then
echo "Custom: ${FCONFIG}"
sh $FCONFIG
fi
#
# If autoconfig parameter was set, reset it and save parameters.
#
if [ $AUTOCNF = yes ]
then
param set SYS_AUTOCONFIG 0
fi
#
# Check if PX4IO present and update firmware if needed.
# Assumption IOFW set to firmware file and IO_PRESENT = no
#
if [ -f $IOFW ]
then
# Check for the mini using build with px4io fw file
# but not a px4IO
if ver hwtypecmp V540
then
param set SYS_USE_IO 0
else
if px4io checkcrc ${IOFW}
then
set IO_PRESENT yes
else
# tune Program PX4IO
tune_control play -t 18
if px4io start
then
# Try to safety px4 io so motor outputs don't go crazy.
if ! px4io safety_on
then
# px4io did not respond to the safety command.
px4io stop
fi
fi
if px4io forceupdate 14662 ${IOFW}
then
usleep 10000
tune_control stop
if px4io checkcrc ${IOFW}
then
echo "PX4IO CRC OK after updating" >> $LOG_FILE
#tune MLL8CDE Program PX4IO success
tune_control play -t 19
set IO_PRESENT yes
fi
fi
if [ $IO_PRESENT = no ]
then
echo "PX4IO update failed" >> $LOG_FILE
# Error tune.
tune_control play -t 20
fi
fi
fi
fi
#
# Set USE_IO flag.
#
if param compare SYS_USE_IO 1
then
set USE_IO yes
fi
if [ $USE_IO = yes -a $IO_PRESENT = no ]
then
echo "PX4IO not found" >> $LOG_FILE
# Error tune.
tune_control play -t 2
fi
if [ $IO_PRESENT = no -o $USE_IO = no ]
then
rc_input start
fi
#
# Sensors System (start before Commander so Preflight checks are properly run).
# Commander needs to be this early for in-air-restarts.
#
if param greater SYS_HITL 0
then
set OUTPUT_MODE hil
sensors start -h
commander start --hil
# disable GPS
param set GPS_1_CONFIG 0
# start the simulator in hardware if needed
if param compare SYS_HITL 2
then
sih start
fi
else
#
# board sensors: rc.sensors
#
set BOARD_RC_SENSORS /etc/init.d/rc.board_sensors
if [ -f $BOARD_RC_SENSORS ]
then
echo "Board sensors: ${BOARD_RC_SENSORS}"
sh $BOARD_RC_SENSORS
fi
unset BOARD_RC_SENSORS
sh /etc/init.d/rc.sensors
commander start
fi
# Sensors on the PWM interface bank.
if param compare SENS_EN_LL40LS 1
then
# Clear pins 5 and 6.
set FMU_MODE pwm4
set AUX_MODE pwm4
fi
if param greater TRIG_MODE 0
then
# We ONLY support trigger on pins 5 and 6 when simultanously using AUX for actuator output.
if param compare TRIG_PINS 56
then
# clear pins 5 and 6
set FMU_MODE pwm4
set AUX_MODE pwm4
else
set FMU_MODE none
set AUX_MODE none
fi
camera_trigger start
camera_feedback start
fi
#
# Check if UAVCAN is enabled, default to it for ESCs.
#
if param greater UAVCAN_ENABLE 0
then
# Start core UAVCAN module.
if uavcan start
then
if param greater UAVCAN_ENABLE 1
then
# Start UAVCAN firmware update server and dynamic node ID allocation server.
uavcan start fw
if param greater UAVCAN_ENABLE 2
then
set OUTPUT_MODE uavcan_esc
fi
fi
else
# Error tune.
tune_control play -t 2
fi
fi
#
# Start mavlink streams that are not configurable (e.g. on USB).
#
sh /etc/init.d/rc.mavlink
#
# Start UART/Serial device drivers.
# Note: rc.serial is auto-generated from Tools/serial/generate_config.py
#
sh /etc/init.d/rc.serial
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.ugv_apps, and rc.vtol_apps.
#
sh /etc/init.d/rc.vehicle_setup
# Camera capture driver
if param greater CAM_CAP_FBACK 0
then
if camera_capture start
then
camera_capture on
fi
fi
#
# Start the navigator.
#
navigator start
#
# Start the standalone wind estimator.
#
if param compare WEST_EN 1
then
wind_estimator start
fi
#
# Start a thermal calibration if required.
#
sh /etc/init.d/rc.thermal_cal
#
# Start vmount to control mounts such as gimbals, disabled by default.
#
if ! param compare MNT_MODE_IN -1
then
vmount start
fi
# Check for flow sensor, launched as a background task to scan
px4flow start &
#
# Optional board supplied extras: rc.board_extras
#
set BOARD_RC_EXTRAS /etc/init.d/rc.board_extras
if [ -f $BOARD_RC_EXTRAS ]
then
echo "Board extras: ${BOARD_RC_EXTRAS}"
sh $BOARD_RC_EXTRAS
fi
unset BOARD_RC_EXTRAS
#
# Start any custom addons from the sdcard.
#
if [ -f $FEXTRAS ]
then
echo "Addons script: ${FEXTRAS}"
sh $FEXTRAS
fi
#
# Start the logger.
#
sh /etc/init.d/rc.logging
if ! param compare SYS_PARAM_VER ${PARAM_DEFAULTS_VER}
then
echo "Switched to different parameter version. Resetting parameters."
param set SYS_PARAM_VER ${PARAM_DEFAULTS_VER}
param set SYS_AUTOCONFIG 2
param save
reboot
fi
#
# End of autostart.
#
fi
#
# Unset all script parameters to free RAM.
#
unset AUTOCNF
unset AUX_MODE
unset DATAMAN_OPT
unset FAILSAFE
unset FAILSAFE_AUX
unset FCONFIG
unset FEXTRAS
unset FMU_ARGS
unset FMU_MODE
unset FRC
unset IO_PRESENT
unset IOFW
unset LOG_FILE
unset LOGGER_ARGS
unset LOGGER_BUF
unset MAV_TYPE
unset MIXER
unset MIXER_AUX
unset MIXER_FILE
unset MK_MODE
unset MKBLCTRL_ARG
unset OUTPUT_MODE
unset PARAM_DEFAULTS_VER
unset PARAM_FILE
unset PWM_AUX_DISARMED
unset PWM_AUX_MAX
unset PWM_AUX_MIN
unset PWM_AUX_OUT
unset PWM_AUX_RATE
unset PWM_DISARMED
unset PWM_MAX
unset PWM_MIN
unset PWM_OUT
unset PWM_RATE
unset SDCARD_MIXERS_PATH
unset USE_IO
unset VEHICLE_TYPE
#
# Boot is complete, inform MAVLink app(s) that the system is now fully up and running.
#
mavlink boot_complete
This file has been truncated. show original
Are you able to do it ? I would also like to log the sonar sensor data only. How can i do it?
Thank you.