From 71d4c7fed8bc809fc38ba54147156fc834d38846 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 5 Feb 2014 19:03:26 +0100 Subject: Startup: Hex vs Hexa --- ROMFS/px4fmu_common/init.d/rcS | 2 +- ROMFS/px4fmu_common/mixers/FMU_hex_+.mix | 3 --- ROMFS/px4fmu_common/mixers/FMU_hex_x.mix | 3 --- ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix | 3 +++ ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix | 3 +++ 5 files changed, 7 insertions(+), 7 deletions(-) delete mode 100644 ROMFS/px4fmu_common/mixers/FMU_hex_+.mix delete mode 100644 ROMFS/px4fmu_common/mixers/FMU_hex_x.mix create mode 100644 ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix create mode 100644 ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 50ac9759a..d12785368 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -465,7 +465,7 @@ then set MAV_TYPE 2 # Use mixer to detect vehicle type - if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ] + if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ] then set MAV_TYPE 13 fi diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix deleted file mode 100644 index e608b459f..000000000 --- a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix +++ /dev/null @@ -1,3 +0,0 @@ -# Hexa + - -R: 6+ 10000 10000 10000 0 diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix deleted file mode 100644 index 16e6e22f9..000000000 --- a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix +++ /dev/null @@ -1,3 +0,0 @@ -# Hexa X - -R: 6x 10000 10000 10000 0 diff --git a/ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix new file mode 100644 index 000000000..e608b459f --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix @@ -0,0 +1,3 @@ +# Hexa + + +R: 6+ 10000 10000 10000 0 diff --git a/ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix new file mode 100644 index 000000000..16e6e22f9 --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix @@ -0,0 +1,3 @@ +# Hexa X + +R: 6x 10000 10000 10000 0 -- cgit v1.2.3 From 3eca9f9b6b866e1c7ad8b57d16ad16cb073d6085 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:11:03 +0100 Subject: Updated logging/conv.zip with latest script versions from Tools directory. --- ROMFS/px4fmu_common/logging/conv.zip | Bin 10087 -> 9922 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ROMFS/px4fmu_common/logging/conv.zip b/ROMFS/px4fmu_common/logging/conv.zip index 7cb837e56..7f485184c 100644 Binary files a/ROMFS/px4fmu_common/logging/conv.zip and b/ROMFS/px4fmu_common/logging/conv.zip differ -- cgit v1.2.3 From 98ee73463f428b420d4aeb44af4a7a90d8d40e41 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:14:40 +0100 Subject: Removed obsolete ROMFS folder for removed logging build. The logging makefile was removed in 9a54c7c6. --- ROMFS/px4fmu_logging/init.d/rcS | 88 ---------------------------------- ROMFS/px4fmu_logging/logging/conv.zip | Bin 10087 -> 0 bytes 2 files changed, 88 deletions(-) delete mode 100644 ROMFS/px4fmu_logging/init.d/rcS delete mode 100644 ROMFS/px4fmu_logging/logging/conv.zip diff --git a/ROMFS/px4fmu_logging/init.d/rcS b/ROMFS/px4fmu_logging/init.d/rcS deleted file mode 100644 index 7b8856719..000000000 --- a/ROMFS/px4fmu_logging/init.d/rcS +++ /dev/null @@ -1,88 +0,0 @@ -#!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 \ No newline at end of file diff --git a/ROMFS/px4fmu_logging/logging/conv.zip b/ROMFS/px4fmu_logging/logging/conv.zip deleted file mode 100644 index 7cb837e56..000000000 Binary files a/ROMFS/px4fmu_logging/logging/conv.zip and /dev/null differ -- cgit v1.2.3 From 1afa53a159ee247a1c57ca59912077c5076c3997 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:15:35 +0100 Subject: Cleanup: Moved sdlog2 file conversion scripts to separate folder. --- Tools/README.txt | 13 -- Tools/logconv.m | 535 -------------------------------------------- Tools/sdlog2/README.txt | 13 ++ Tools/sdlog2/logconv.m | 535 ++++++++++++++++++++++++++++++++++++++++++++ Tools/sdlog2/sdlog2_dump.py | 334 +++++++++++++++++++++++++++ Tools/sdlog2_dump.py | 334 --------------------------- 6 files changed, 882 insertions(+), 882 deletions(-) delete mode 100644 Tools/README.txt delete mode 100644 Tools/logconv.m create mode 100644 Tools/sdlog2/README.txt create mode 100644 Tools/sdlog2/logconv.m create mode 100644 Tools/sdlog2/sdlog2_dump.py delete mode 100644 Tools/sdlog2_dump.py diff --git a/Tools/README.txt b/Tools/README.txt deleted file mode 100644 index abeb9a4c7..000000000 --- a/Tools/README.txt +++ /dev/null @@ -1,13 +0,0 @@ -====== PX4 LOG CONVERSION ====== - -On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight). - -There are two conversion scripts in this ZIP file: - -logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored. - -sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run: - -python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n "" - -Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux. \ No newline at end of file diff --git a/Tools/logconv.m b/Tools/logconv.m deleted file mode 100644 index c416b8095..000000000 --- a/Tools/logconv.m +++ /dev/null @@ -1,535 +0,0 @@ -% This Matlab Script can be used to import the binary logged values of the -% PX4FMU into data that can be plotted and analyzed. - -%% ************************************************************************ -% PX4LOG_PLOTSCRIPT: Main function -% ************************************************************************ -function PX4Log_Plotscript - -% Clear everything -clc -clear all -close all - -% ************************************************************************ -% SETTINGS -% ************************************************************************ - -% Set the path to your sysvector.bin file here -filePath = 'log001.bin'; - -% Set the minimum and maximum times to plot here [in seconds] -mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] -maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] - -%Determine which data to plot. Not completely implemented yet. -bDisplayGPS=true; - -%conversion factors -fconv_gpsalt=1; %[mm] to [m] -fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] -fconv_timestamp=1E-6; % [microseconds] to [seconds] - -% ************************************************************************ -% Import the PX4 logs -% ************************************************************************ -ImportPX4LogData(); - -%Translate min and max plot times to indices -time=double(sysvector.TIME_StartTime) .*fconv_timestamp; -mintime_log=time(1); %The minimum time/timestamp found in the log -maxtime_log=time(end); %The maximum time/timestamp found in the log -CurTime=mintime_log; %The current time at which to draw the aircraft position - -[imintime,imaxtime]=FindMinMaxTimeIndices(); - -% ************************************************************************ -% PLOT & GUI SETUP -% ************************************************************************ -NrFigures=5; -NrAxes=10; -h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively -h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively -h.pathpoints=[]; % Temporary initiliazation of path points - -% Setup the GUI to control the plots -InitControlGUI(); -% Setup the plotting-GUI (figures, axes) itself. -InitPlotGUI(); - -% ************************************************************************ -% DRAW EVERYTHING -% ************************************************************************ -DrawRawData(); -DrawCurrentAircraftState(); - -%% ************************************************************************ -% *** END OF MAIN SCRIPT *** -% NESTED FUNCTION DEFINTIONS FROM HERE ON -% ************************************************************************ - - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -function ImportPX4LogData() - - % ************************************************************************ - % RETRIEVE SYSTEM VECTOR - % ************************************************************************* - % //All measurements in NED frame - - % Convert to CSV - %arg1 = 'log-fx61-20130721-2.bin'; - arg1 = filePath; - delim = ','; - time_field = 'TIME'; - data_file = 'data.csv'; - csv_null = ''; - - if not(exist(data_file, 'file')) - s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); - end - - if exist(data_file, 'file') - - %data = csvread(data_file); - sysvector = tdfread(data_file, ','); - - % shot the flight time - time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); - time_s = uint64(time_us*1e-6); - time_m = uint64(time_s/60); - time_s = time_s - time_m * 60; - - disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); - - disp(['logfile conversion finished.' char(10)]); - else - disp(['file: ' data_file ' does not exist' char(10)]); - end -end - -%% ************************************************************************ -% INITCONTROLGUI (nested function) -% ************************************************************************ -%Setup central control GUI components to control current time where data is shown -function InitControlGUI() - %********************************************************************** - % GUI size definitions - %********************************************************************** - dxy=5; %margins - %Panel: Plotctrl - dlabels=120; - dsliders=200; - dedits=80; - hslider=20; - - hpanel1=40; %panel1 - hpanel2=220;%panel2 - hpanel3=3*hslider+4*dxy+3*dxy;%panel3. - - width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width - height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height - - %********************************************************************** - % Create GUI - %********************************************************************** - h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); - h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); - h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); - h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); - - %%Control GUI-elements - %Slider: Current time - h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... - 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); - temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); - set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); - h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... - 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); - - %Slider: MaxTime - h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %Slider: MinTime - h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %%Current data/state GUI-elements (Multiline-edit-box) - h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... - 'HorizontalAlignment','left','parent',h.aircraftstatepanel); - - h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... - 'HorizontalAlignment','left','parent',h.guistatepanel); - -end - -%% ************************************************************************ -% INITPLOTGUI (nested function) -% ************************************************************************ -function InitPlotGUI() - - % Setup handles to lines and text - h.markertext=[]; - templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array - h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively - h.markerline(1:NrAxes)=0.0; - - % Setup all other figures and axes for plotting - % PLOT WINDOW 1: GPS POSITION - h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); - h.axes(1)=axes(); - set(h.axes(1),'Parent',h.figures(2)); - - % PLOT WINDOW 2: IMU, baro altitude - h.figures(3)=figure('Name', 'IMU / Baro Altitude'); - h.axes(2)=subplot(4,1,1); - h.axes(3)=subplot(4,1,2); - h.axes(4)=subplot(4,1,3); - h.axes(5)=subplot(4,1,4); - set(h.axes(2:5),'Parent',h.figures(3)); - - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); - h.axes(6)=subplot(4,1,1); - h.axes(7)=subplot(4,1,2); - h.axes(8)=subplot(4,1,3); - h.axes(9)=subplot(4,1,4); - set(h.axes(6:9),'Parent',h.figures(4)); - - % PLOT WINDOW 4: LOG STATS - h.figures(5) = figure('Name', 'Log Statistics'); - h.axes(10)=subplot(1,1,1); - set(h.axes(10:10),'Parent',h.figures(5)); - -end - -%% ************************************************************************ -% DRAWRAWDATA (nested function) -% ************************************************************************ -%Draws the raw data from the sysvector, but does not add any -%marker-lines or so -function DrawRawData() - % ************************************************************************ - % PLOT WINDOW 1: GPS POSITION & GUI - % ************************************************************************ - figure(h.figures(2)); - % Only plot GPS data if available - if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) - %Draw data - plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); - title(h.axes(1),'GPS Position Data(if available)'); - xlabel(h.axes(1),'Latitude [deg]'); - ylabel(h.axes(1),'Longitude [deg]'); - zlabel(h.axes(1),'Altitude above MSL [m]'); - grid on - - %Reset path - h.pathpoints=0; - end - - % ************************************************************************ - % PLOT WINDOW 2: IMU, baro altitude - % ************************************************************************ - figure(h.figures(3)); - plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); - title(h.axes(2),'Magnetometers [Gauss]'); - legend(h.axes(2),'x','y','z'); - plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); - title(h.axes(3),'Accelerometers [m/s²]'); - legend(h.axes(3),'x','y','z'); - plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); - title(h.axes(4),'Gyroscopes [rad/s]'); - legend(h.axes(4),'x','y','z'); - plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); - if(bDisplayGPS) - hold on; - plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); - hold off - legend('Barometric Altitude [m]','GPS Altitude [m]'); - else - legend('Barometric Altitude [m]'); - end - title(h.axes(5),'Altitude above MSL [m]'); - - % ************************************************************************ - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - % ************************************************************************ - figure(h.figures(4)); - %Attitude Estimate - plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); - title(h.axes(6),'Estimated attitude [deg]'); - legend(h.axes(6),'roll','pitch','yaw'); - %Actuator Controls - plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); - title(h.axes(7),'Actuator control [-]'); - legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); - %Actuator Controls - plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); - title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); - legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); - set(h.axes(8), 'YLim',[800 2200]); - %Airspeeds - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); - hold on - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); - hold off - %add GPS total airspeed here - title(h.axes(9),'Airspeed [m/s]'); - legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); - %calculate time differences and plot them - intervals = zeros(0,imaxtime - imintime); - for k = imintime+1:imaxtime - intervals(k) = time(k) - time(k-1); - end - plot(h.axes(10), time(imintime:imaxtime), intervals); - - %Set same timescale for all plots - for i=2:NrAxes - set(h.axes(i),'XLim',[mintime maxtime]); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% DRAWCURRENTAIRCRAFTSTATE(nested function) -% ************************************************************************ -function DrawCurrentAircraftState() - %find current data index - i=find(time>=CurTime,1,'first'); - - %********************************************************************** - % Current aircraft state label update - %********************************************************************** - acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... - 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... - 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... - ', y=',num2str(sysvector.IMU_MagY(i)),... - ', z=',num2str(sysvector.IMU_MagZ(i)),']']; - acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... - ', y=',num2str(sysvector.IMU_AccY(i)),... - ', z=',num2str(sysvector.IMU_AccZ(i)),']']; - acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... - ', y=',num2str(sysvector.IMU_GyroY(i)),... - ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; - acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... - ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... - ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; - acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); - %for j=1:4 - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; - %end - acstate{7,:}=[acstate{7,:},']']; - acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); - %for j=1:8 - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; - %end - acstate{8,:}=[acstate{8,:},']']; - acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; - - set(h.edits.AircraftState,'String',acstate); - - %********************************************************************** - % GPS Plot Update - %********************************************************************** - %Plot traveled path, and and time. - figure(h.figures(2)); - hold on; - if(CurTime>mintime+1) %the +1 is only a small bugfix - h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); - end; - hold off - %Plot current position - newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; - if(numel(h.pathpoints)<=3) %empty path - h.pathpoints(1,1:3)=newpoint; - else %Not empty, append new point - h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; - end - axes(h.axes(1)); - line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); - - - % Plot current time (small label next to current gps position) - textdesc=strcat(' t=',num2str(time(i)),'s'); - if(isvalidhandle(h.markertext)) - delete(h.markertext); %delete old text - end - h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... - double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); - set(h.edits.CurTime,'String',CurTime); - - %********************************************************************** - % Plot the lines showing the current time in the 2-d plots - %********************************************************************** - for i=2:NrAxes - if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end - ylims=get(h.axes(i),'YLim'); - h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); - set(h.markerline(i),'parent',h.axes(i)); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% MINMAXTIME CALLBACK (nested function) -% ************************************************************************ -function minmaxtime_callback(hObj,event) %#ok - new_mintime=get(h.sliders.MinTime,'Value'); - new_maxtime=get(h.sliders.MaxTime,'Value'); - - %Safety checks: - bErr=false; - %1: mintime must be < maxtime - if((new_mintime>maxtime) || (new_maxtimeCurTime) - set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); - mintime=new_mintime; - CurTime=mintime; - bErr=true; - end - %3: MaxTime must be >CurTime - if(new_maxtime - %find current time - if(hObj==h.sliders.CurTime) - CurTime=get(h.sliders.CurTime,'Value'); - elseif (hObj==h.edits.CurTime) - temp=str2num(get(h.edits.CurTime,'String')); - if(tempmintime) - CurTime=temp; - else - %Error - set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); - end - else - %Error - set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); - end - - set(h.sliders.CurTime,'Value',CurTime); - set(h.edits.CurTime,'String',num2str(CurTime)); - - %Redraw time markers, but don't have to redraw the whole raw data - DrawCurrentAircraftState(); -end - -%% ************************************************************************ -% FINDMINMAXINDICES (nested function) -% ************************************************************************ -function [idxmin,idxmax] = FindMinMaxTimeIndices() - for i=1:size(sysvector.TIME_StartTime,1) - if time(i)>=mintime; idxmin=i; break; end - end - for i=1:size(sysvector.TIME_StartTime,1) - if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end - if time(i)>=maxtime; idxmax=i; break; end - end - mintime=time(idxmin); - maxtime=time(idxmax); -end - -%% ************************************************************************ -% ISVALIDHANDLE (nested function) -% ************************************************************************ -function isvalid = isvalidhandle(handle) - if(exist(varname(handle))>0 && length(ishandle(handle))>0) - if(ishandle(handle)>0) - if(handle>0.0) - isvalid=true; - return; - end - end - end - isvalid=false; -end - -%% ************************************************************************ -% JUST SOME SMALL HELPER FUNCTIONS (nested function) -% ************************************************************************ -function out = varname(var) - out = inputname(1); -end - -%This is the end of the matlab file / the main function -end diff --git a/Tools/sdlog2/README.txt b/Tools/sdlog2/README.txt new file mode 100644 index 000000000..abeb9a4c7 --- /dev/null +++ b/Tools/sdlog2/README.txt @@ -0,0 +1,13 @@ +====== PX4 LOG CONVERSION ====== + +On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight). + +There are two conversion scripts in this ZIP file: + +logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored. + +sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run: + +python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n "" + +Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux. \ No newline at end of file diff --git a/Tools/sdlog2/logconv.m b/Tools/sdlog2/logconv.m new file mode 100644 index 000000000..e19c97fa3 --- /dev/null +++ b/Tools/sdlog2/logconv.m @@ -0,0 +1,535 @@ +% This Matlab Script can be used to import the binary logged values of the +% PX4FMU into data that can be plotted and analyzed. + +%% ************************************************************************ +% PX4LOG_PLOTSCRIPT: Main function +% ************************************************************************ +function PX4Log_Plotscript + +% Clear everything +clc +clear all +close all + +% ************************************************************************ +% SETTINGS +% ************************************************************************ + +% Set the path to your sysvector.bin file here +filePath = 'log001.bin'; + +% Set the minimum and maximum times to plot here [in seconds] +mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] +maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] + +%Determine which data to plot. Not completely implemented yet. +bDisplayGPS=true; + +%conversion factors +fconv_gpsalt=1; %[mm] to [m] +fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] +fconv_timestamp=1E-6; % [microseconds] to [seconds] + +% ************************************************************************ +% Import the PX4 logs +% ************************************************************************ +ImportPX4LogData(); + +%Translate min and max plot times to indices +time=double(sysvector.TIME_StartTime) .*fconv_timestamp; +mintime_log=time(1); %The minimum time/timestamp found in the log +maxtime_log=time(end); %The maximum time/timestamp found in the log +CurTime=mintime_log; %The current time at which to draw the aircraft position + +[imintime,imaxtime]=FindMinMaxTimeIndices(); + +% ************************************************************************ +% PLOT & GUI SETUP +% ************************************************************************ +NrFigures=5; +NrAxes=10; +h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively +h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively +h.pathpoints=[]; % Temporary initiliazation of path points + +% Setup the GUI to control the plots +InitControlGUI(); +% Setup the plotting-GUI (figures, axes) itself. +InitPlotGUI(); + +% ************************************************************************ +% DRAW EVERYTHING +% ************************************************************************ +DrawRawData(); +DrawCurrentAircraftState(); + +%% ************************************************************************ +% *** END OF MAIN SCRIPT *** +% NESTED FUNCTION DEFINTIONS FROM HERE ON +% ************************************************************************ + + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +function ImportPX4LogData() + + % ************************************************************************ + % RETRIEVE SYSTEM VECTOR + % ************************************************************************* + % //All measurements in NED frame + + % Convert to CSV + %arg1 = 'log-fx61-20130721-2.bin'; + arg1 = filePath; + delim = ','; + time_field = 'TIME'; + data_file = 'data.csv'; + csv_null = ''; + + if not(exist(data_file, 'file')) + s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); + end + + if exist(data_file, 'file') + + %data = csvread(data_file); + sysvector = tdfread(data_file, ','); + + % shot the flight time + time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); + time_s = uint64(time_us*1e-6); + time_m = uint64(time_s/60); + time_s = time_s - time_m * 60; + + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); + + disp(['logfile conversion finished.' char(10)]); + else + disp(['file: ' data_file ' does not exist' char(10)]); + end +end + +%% ************************************************************************ +% INITCONTROLGUI (nested function) +% ************************************************************************ +%Setup central control GUI components to control current time where data is shown +function InitControlGUI() + %********************************************************************** + % GUI size definitions + %********************************************************************** + dxy=5; %margins + %Panel: Plotctrl + dlabels=120; + dsliders=200; + dedits=80; + hslider=20; + + hpanel1=40; %panel1 + hpanel2=220;%panel2 + hpanel3=3*hslider+4*dxy+3*dxy;%panel3. + + width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width + height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height + + %********************************************************************** + % Create GUI + %********************************************************************** + h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); + h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); + h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); + h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); + + %%Control GUI-elements + %Slider: Current time + h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... + 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); + temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); + set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); + h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... + 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); + + %Slider: MaxTime + h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %Slider: MinTime + h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %%Current data/state GUI-elements (Multiline-edit-box) + h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... + 'HorizontalAlignment','left','parent',h.aircraftstatepanel); + + h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... + 'HorizontalAlignment','left','parent',h.guistatepanel); + +end + +%% ************************************************************************ +% INITPLOTGUI (nested function) +% ************************************************************************ +function InitPlotGUI() + + % Setup handles to lines and text + h.markertext=[]; + templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array + h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively + h.markerline(1:NrAxes)=0.0; + + % Setup all other figures and axes for plotting + % PLOT WINDOW 1: GPS POSITION + h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); + h.axes(1)=axes(); + set(h.axes(1),'Parent',h.figures(2)); + + % PLOT WINDOW 2: IMU, baro altitude + h.figures(3)=figure('Name', 'IMU / Baro Altitude'); + h.axes(2)=subplot(4,1,1); + h.axes(3)=subplot(4,1,2); + h.axes(4)=subplot(4,1,3); + h.axes(5)=subplot(4,1,4); + set(h.axes(2:5),'Parent',h.figures(3)); + + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); + h.axes(6)=subplot(4,1,1); + h.axes(7)=subplot(4,1,2); + h.axes(8)=subplot(4,1,3); + h.axes(9)=subplot(4,1,4); + set(h.axes(6:9),'Parent',h.figures(4)); + + % PLOT WINDOW 4: LOG STATS + h.figures(5) = figure('Name', 'Log Statistics'); + h.axes(10)=subplot(1,1,1); + set(h.axes(10:10),'Parent',h.figures(5)); + +end + +%% ************************************************************************ +% DRAWRAWDATA (nested function) +% ************************************************************************ +%Draws the raw data from the sysvector, but does not add any +%marker-lines or so +function DrawRawData() + % ************************************************************************ + % PLOT WINDOW 1: GPS POSITION & GUI + % ************************************************************************ + figure(h.figures(2)); + % Only plot GPS data if available + if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) + %Draw data + plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); + title(h.axes(1),'GPS Position Data(if available)'); + xlabel(h.axes(1),'Latitude [deg]'); + ylabel(h.axes(1),'Longitude [deg]'); + zlabel(h.axes(1),'Altitude above MSL [m]'); + grid on + + %Reset path + h.pathpoints=0; + end + + % ************************************************************************ + % PLOT WINDOW 2: IMU, baro altitude + % ************************************************************************ + figure(h.figures(3)); + plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); + title(h.axes(2),'Magnetometers [Gauss]'); + legend(h.axes(2),'x','y','z'); + plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); + title(h.axes(3),'Accelerometers [m/s²]'); + legend(h.axes(3),'x','y','z'); + plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); + title(h.axes(4),'Gyroscopes [rad/s]'); + legend(h.axes(4),'x','y','z'); + plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); + if(bDisplayGPS) + hold on; + plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); + hold off + legend('Barometric Altitude [m]','GPS Altitude [m]'); + else + legend('Barometric Altitude [m]'); + end + title(h.axes(5),'Altitude above MSL [m]'); + + % ************************************************************************ + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + % ************************************************************************ + figure(h.figures(4)); + %Attitude Estimate + plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); + title(h.axes(6),'Estimated attitude [deg]'); + legend(h.axes(6),'roll','pitch','yaw'); + %Actuator Controls + plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); + title(h.axes(7),'Actuator control [-]'); + legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); + %Actuator Controls + plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); + title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); + legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); + set(h.axes(8), 'YLim',[800 2200]); + %Airspeeds + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); + hold on + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); + hold off + %add GPS total airspeed here + title(h.axes(9),'Airspeed [m/s]'); + legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); + %calculate time differences and plot them + intervals = zeros(0,imaxtime - imintime); + for k = imintime+1:imaxtime + intervals(k) = time(k) - time(k-1); + end + plot(h.axes(10), time(imintime:imaxtime), intervals); + + %Set same timescale for all plots + for i=2:NrAxes + set(h.axes(i),'XLim',[mintime maxtime]); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% DRAWCURRENTAIRCRAFTSTATE(nested function) +% ************************************************************************ +function DrawCurrentAircraftState() + %find current data index + i=find(time>=CurTime,1,'first'); + + %********************************************************************** + % Current aircraft state label update + %********************************************************************** + acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... + 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... + 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... + ', y=',num2str(sysvector.IMU_MagY(i)),... + ', z=',num2str(sysvector.IMU_MagZ(i)),']']; + acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... + ', y=',num2str(sysvector.IMU_AccY(i)),... + ', z=',num2str(sysvector.IMU_AccZ(i)),']']; + acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... + ', y=',num2str(sysvector.IMU_GyroY(i)),... + ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; + acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... + ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... + ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; + acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); + %for j=1:4 + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; + %end + acstate{7,:}=[acstate{7,:},']']; + acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); + %for j=1:8 + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; + %end + acstate{8,:}=[acstate{8,:},']']; + acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; + + set(h.edits.AircraftState,'String',acstate); + + %********************************************************************** + % GPS Plot Update + %********************************************************************** + %Plot traveled path, and and time. + figure(h.figures(2)); + hold on; + if(CurTime>mintime+1) %the +1 is only a small bugfix + h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); + end; + hold off + %Plot current position + newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; + if(numel(h.pathpoints)<=3) %empty path + h.pathpoints(1,1:3)=newpoint; + else %Not empty, append new point + h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; + end + axes(h.axes(1)); + line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); + + + % Plot current time (small label next to current gps position) + textdesc=strcat(' t=',num2str(time(i)),'s'); + if(isvalidhandle(h.markertext)) + delete(h.markertext); %delete old text + end + h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... + double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); + set(h.edits.CurTime,'String',CurTime); + + %********************************************************************** + % Plot the lines showing the current time in the 2-d plots + %********************************************************************** + for i=2:NrAxes + if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end + ylims=get(h.axes(i),'YLim'); + h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); + set(h.markerline(i),'parent',h.axes(i)); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% MINMAXTIME CALLBACK (nested function) +% ************************************************************************ +function minmaxtime_callback(hObj,event) %#ok + new_mintime=get(h.sliders.MinTime,'Value'); + new_maxtime=get(h.sliders.MaxTime,'Value'); + + %Safety checks: + bErr=false; + %1: mintime must be < maxtime + if((new_mintime>maxtime) || (new_maxtimeCurTime) + set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); + mintime=new_mintime; + CurTime=mintime; + bErr=true; + end + %3: MaxTime must be >CurTime + if(new_maxtime + %find current time + if(hObj==h.sliders.CurTime) + CurTime=get(h.sliders.CurTime,'Value'); + elseif (hObj==h.edits.CurTime) + temp=str2num(get(h.edits.CurTime,'String')); + if(tempmintime) + CurTime=temp; + else + %Error + set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); + end + else + %Error + set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); + end + + set(h.sliders.CurTime,'Value',CurTime); + set(h.edits.CurTime,'String',num2str(CurTime)); + + %Redraw time markers, but don't have to redraw the whole raw data + DrawCurrentAircraftState(); +end + +%% ************************************************************************ +% FINDMINMAXINDICES (nested function) +% ************************************************************************ +function [idxmin,idxmax] = FindMinMaxTimeIndices() + for i=1:size(sysvector.TIME_StartTime,1) + if time(i)>=mintime; idxmin=i; break; end + end + for i=1:size(sysvector.TIME_StartTime,1) + if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end + if time(i)>=maxtime; idxmax=i; break; end + end + mintime=time(idxmin); + maxtime=time(idxmax); +end + +%% ************************************************************************ +% ISVALIDHANDLE (nested function) +% ************************************************************************ +function isvalid = isvalidhandle(handle) + if(exist(varname(handle))>0 && length(ishandle(handle))>0) + if(ishandle(handle)>0) + if(handle>0.0) + isvalid=true; + return; + end + end + end + isvalid=false; +end + +%% ************************************************************************ +% JUST SOME SMALL HELPER FUNCTIONS (nested function) +% ************************************************************************ +function out = varname(var) + out = inputname(1); +end + +%This is the end of the matlab file / the main function +end diff --git a/Tools/sdlog2/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py new file mode 100644 index 000000000..5b1e55e22 --- /dev/null +++ b/Tools/sdlog2/sdlog2_dump.py @@ -0,0 +1,334 @@ +#!/usr/bin/env python + +from __future__ import print_function + +"""Dump binary log generated by PX4's sdlog2 or APM as CSV + +Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] + + -v Use plain debug output instead of CSV. + + -e Recover from errors. + + -d Use "delimiter" in CSV. Default is ",". + + -n Use "null" as placeholder for empty values in CSV. Default is empty. + + -m MSG[.field1,field2,...] + Dump only messages of specified type, and only specified fields. + Multiple -m options allowed.""" + +__author__ = "Anton Babushkin" +__version__ = "1.2" + +import struct, sys + +if sys.hexversion >= 0x030000F0: + runningPython3 = True + def _parseCString(cstr): + return str(cstr, 'ascii').split('\0')[0] +else: + runningPython3 = False + def _parseCString(cstr): + return str(cstr).split('\0')[0] + +class SDLog2Parser: + BLOCK_SIZE = 8192 + MSG_HEADER_LEN = 3 + MSG_HEAD1 = 0xA3 + MSG_HEAD2 = 0x95 + MSG_FORMAT_PACKET_LEN = 89 + MSG_FORMAT_STRUCT = "BB4s16s64s" + MSG_TYPE_FORMAT = 0x80 + FORMAT_TO_STRUCT = { + "b": ("b", None), + "B": ("B", None), + "h": ("h", None), + "H": ("H", None), + "i": ("i", None), + "I": ("I", None), + "f": ("f", None), + "n": ("4s", None), + "N": ("16s", None), + "Z": ("64s", None), + "c": ("h", 0.01), + "C": ("H", 0.01), + "e": ("i", 0.01), + "E": ("I", 0.01), + "L": ("i", 0.0000001), + "M": ("b", None), + "q": ("q", None), + "Q": ("Q", None), + } + __csv_delim = "," + __csv_null = "" + __msg_filter = [] + __time_msg = None + __debug_out = False + __correct_errors = False + __file_name = None + __file = None + + def __init__(self): + return + + def reset(self): + self.__msg_descrs = {} # message descriptions by message type map + self.__msg_labels = {} # message labels by message name map + self.__msg_names = [] # message names in the same order as FORMAT messages + self.__buffer = bytearray() # buffer for input binary data + self.__ptr = 0 # read pointer in buffer + self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" + self.__csv_data = {} # current values for all columns + self.__csv_updated = False + self.__msg_filter_map = {} # filter in form of map, with '*" expanded to full list of fields + + def setCSVDelimiter(self, csv_delim): + self.__csv_delim = csv_delim + + def setCSVNull(self, csv_null): + self.__csv_null = csv_null + + def setMsgFilter(self, msg_filter): + self.__msg_filter = msg_filter + + def setTimeMsg(self, time_msg): + self.__time_msg = time_msg + + def setDebugOut(self, debug_out): + self.__debug_out = debug_out + + def setCorrectErrors(self, correct_errors): + self.__correct_errors = correct_errors + + def setFileName(self, file_name): + self.__file_name = file_name + if file_name != None: + self.__file = open(file_name, 'w+') + else: + self.__file = None + + + def process(self, fn): + self.reset() + if self.__debug_out: + # init __msg_filter_map + for msg_name, show_fields in self.__msg_filter: + self.__msg_filter_map[msg_name] = show_fields + first_data_msg = True + f = open(fn, "rb") + bytes_read = 0 + while True: + chunk = f.read(self.BLOCK_SIZE) + if len(chunk) == 0: + break + self.__buffer = self.__buffer[self.__ptr:] + chunk + self.__ptr = 0 + while self.__bytesLeft() >= self.MSG_HEADER_LEN: + head1 = self.__buffer[self.__ptr] + head2 = self.__buffer[self.__ptr+1] + if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): + if self.__correct_errors: + self.__ptr += 1 + continue + else: + raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) + msg_type = self.__buffer[self.__ptr+2] + if msg_type == self.MSG_TYPE_FORMAT: + # parse FORMAT message + if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: + break + self.__parseMsgDescr() + else: + # parse data message + msg_descr = self.__msg_descrs[msg_type] + if msg_descr == None: + raise Exception("Unknown msg type: %i" % msg_type) + msg_length = msg_descr[0] + if self.__bytesLeft() < msg_length: + break + if first_data_msg: + # build CSV columns and init data map + self.__initCSV() + first_data_msg = False + self.__parseMsg(msg_descr) + bytes_read += self.__ptr + if not self.__debug_out and self.__time_msg != None and self.__csv_updated: + self.__printCSVRow() + f.close() + + def __bytesLeft(self): + return len(self.__buffer) - self.__ptr + + def __filterMsg(self, msg_name): + show_fields = "*" + if len(self.__msg_filter_map) > 0: + show_fields = self.__msg_filter_map.get(msg_name) + return show_fields + + def __initCSV(self): + if len(self.__msg_filter) == 0: + for msg_name in self.__msg_names: + self.__msg_filter.append((msg_name, "*")) + for msg_name, show_fields in self.__msg_filter: + if show_fields == "*": + show_fields = self.__msg_labels.get(msg_name, []) + self.__msg_filter_map[msg_name] = show_fields + for field in show_fields: + full_label = msg_name + "_" + field + self.__csv_columns.append(full_label) + self.__csv_data[full_label] = None + if self.__file != None: + print(self.__csv_delim.join(self.__csv_columns), file=self.__file) + else: + print(self.__csv_delim.join(self.__csv_columns)) + + def __printCSVRow(self): + s = [] + for full_label in self.__csv_columns: + v = self.__csv_data[full_label] + if v == None: + v = self.__csv_null + else: + v = str(v) + s.append(v) + + if self.__file != None: + print(self.__csv_delim.join(s), file=self.__file) + else: + print(self.__csv_delim.join(s)) + + def __parseMsgDescr(self): + if runningPython3: + data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) + else: + data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) + msg_type = data[0] + if msg_type != self.MSG_TYPE_FORMAT: + msg_length = data[1] + msg_name = _parseCString(data[2]) + msg_format = _parseCString(data[3]) + msg_labels = _parseCString(data[4]).split(",") + # Convert msg_format to struct.unpack format string + msg_struct = "" + msg_mults = [] + for c in msg_format: + try: + f = self.FORMAT_TO_STRUCT[c] + msg_struct += f[0] + msg_mults.append(f[1]) + except KeyError as e: + raise Exception("Unsupported format char: %s in message %s (%i)" % (c, msg_name, msg_type)) + msg_struct = "<" + msg_struct # force little-endian + self.__msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) + self.__msg_labels[msg_name] = msg_labels + self.__msg_names.append(msg_name) + if self.__debug_out: + if self.__filterMsg(msg_name) != None: + print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( + msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) + self.__ptr += self.MSG_FORMAT_PACKET_LEN + + def __parseMsg(self, msg_descr): + msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr + if not self.__debug_out and self.__time_msg != None and msg_name == self.__time_msg and self.__csv_updated: + self.__printCSVRow() + self.__csv_updated = False + show_fields = self.__filterMsg(msg_name) + if (show_fields != None): + if runningPython3: + data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) + else: + data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))) + for i in range(len(data)): + if type(data[i]) is str: + data[i] = _parseCString(data[i]) + m = msg_mults[i] + if m != None: + data[i] = data[i] * m + if self.__debug_out: + s = [] + for i in range(len(data)): + label = msg_labels[i] + if show_fields == "*" or label in show_fields: + s.append(label + "=" + str(data[i])) + print("MSG %s: %s" % (msg_name, ", ".join(s))) + else: + # update CSV data buffer + for i in range(len(data)): + label = msg_labels[i] + if label in show_fields: + self.__csv_data[msg_name + "_" + label] = data[i] + if self.__time_msg != None and msg_name != self.__time_msg: + self.__csv_updated = True + if self.__time_msg == None: + self.__printCSVRow() + self.__ptr += msg_length + +def _main(): + if len(sys.argv) < 2: + print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") + print("\t-v\tUse plain debug output instead of CSV.\n") + print("\t-e\tRecover from errors.\n") + print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n") + print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n") + print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") + print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") + print("\t-fPrint to file instead of stdout") + return + fn = sys.argv[1] + debug_out = False + correct_errors = False + msg_filter = [] + csv_null = "" + csv_delim = "," + time_msg = "TIME" + file_name = None + opt = None + for arg in sys.argv[2:]: + if opt != None: + if opt == "d": + csv_delim = arg + elif opt == "n": + csv_null = arg + elif opt == "t": + time_msg = arg + elif opt == "f": + file_name = arg + elif opt == "m": + show_fields = "*" + a = arg.split("_") + if len(a) > 1: + show_fields = a[1].split(",") + msg_filter.append((a[0], show_fields)) + opt = None + else: + if arg == "-v": + debug_out = True + elif arg == "-e": + correct_errors = True + elif arg == "-d": + opt = "d" + elif arg == "-n": + opt = "n" + elif arg == "-m": + opt = "m" + elif arg == "-t": + opt = "t" + elif arg == "-f": + opt = "f" + + if csv_delim == "\\t": + csv_delim = "\t" + parser = SDLog2Parser() + parser.setCSVDelimiter(csv_delim) + parser.setCSVNull(csv_null) + parser.setMsgFilter(msg_filter) + parser.setTimeMsg(time_msg) + parser.setFileName(file_name) + parser.setDebugOut(debug_out) + parser.setCorrectErrors(correct_errors) + parser.process(fn) + +if __name__ == "__main__": + _main() diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py deleted file mode 100644 index 5b1e55e22..000000000 --- a/Tools/sdlog2_dump.py +++ /dev/null @@ -1,334 +0,0 @@ -#!/usr/bin/env python - -from __future__ import print_function - -"""Dump binary log generated by PX4's sdlog2 or APM as CSV - -Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] - - -v Use plain debug output instead of CSV. - - -e Recover from errors. - - -d Use "delimiter" in CSV. Default is ",". - - -n Use "null" as placeholder for empty values in CSV. Default is empty. - - -m MSG[.field1,field2,...] - Dump only messages of specified type, and only specified fields. - Multiple -m options allowed.""" - -__author__ = "Anton Babushkin" -__version__ = "1.2" - -import struct, sys - -if sys.hexversion >= 0x030000F0: - runningPython3 = True - def _parseCString(cstr): - return str(cstr, 'ascii').split('\0')[0] -else: - runningPython3 = False - def _parseCString(cstr): - return str(cstr).split('\0')[0] - -class SDLog2Parser: - BLOCK_SIZE = 8192 - MSG_HEADER_LEN = 3 - MSG_HEAD1 = 0xA3 - MSG_HEAD2 = 0x95 - MSG_FORMAT_PACKET_LEN = 89 - MSG_FORMAT_STRUCT = "BB4s16s64s" - MSG_TYPE_FORMAT = 0x80 - FORMAT_TO_STRUCT = { - "b": ("b", None), - "B": ("B", None), - "h": ("h", None), - "H": ("H", None), - "i": ("i", None), - "I": ("I", None), - "f": ("f", None), - "n": ("4s", None), - "N": ("16s", None), - "Z": ("64s", None), - "c": ("h", 0.01), - "C": ("H", 0.01), - "e": ("i", 0.01), - "E": ("I", 0.01), - "L": ("i", 0.0000001), - "M": ("b", None), - "q": ("q", None), - "Q": ("Q", None), - } - __csv_delim = "," - __csv_null = "" - __msg_filter = [] - __time_msg = None - __debug_out = False - __correct_errors = False - __file_name = None - __file = None - - def __init__(self): - return - - def reset(self): - self.__msg_descrs = {} # message descriptions by message type map - self.__msg_labels = {} # message labels by message name map - self.__msg_names = [] # message names in the same order as FORMAT messages - self.__buffer = bytearray() # buffer for input binary data - self.__ptr = 0 # read pointer in buffer - self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label" - self.__csv_data = {} # current values for all columns - self.__csv_updated = False - self.__msg_filter_map = {} # filter in form of map, with '*" expanded to full list of fields - - def setCSVDelimiter(self, csv_delim): - self.__csv_delim = csv_delim - - def setCSVNull(self, csv_null): - self.__csv_null = csv_null - - def setMsgFilter(self, msg_filter): - self.__msg_filter = msg_filter - - def setTimeMsg(self, time_msg): - self.__time_msg = time_msg - - def setDebugOut(self, debug_out): - self.__debug_out = debug_out - - def setCorrectErrors(self, correct_errors): - self.__correct_errors = correct_errors - - def setFileName(self, file_name): - self.__file_name = file_name - if file_name != None: - self.__file = open(file_name, 'w+') - else: - self.__file = None - - - def process(self, fn): - self.reset() - if self.__debug_out: - # init __msg_filter_map - for msg_name, show_fields in self.__msg_filter: - self.__msg_filter_map[msg_name] = show_fields - first_data_msg = True - f = open(fn, "rb") - bytes_read = 0 - while True: - chunk = f.read(self.BLOCK_SIZE) - if len(chunk) == 0: - break - self.__buffer = self.__buffer[self.__ptr:] + chunk - self.__ptr = 0 - while self.__bytesLeft() >= self.MSG_HEADER_LEN: - head1 = self.__buffer[self.__ptr] - head2 = self.__buffer[self.__ptr+1] - if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2): - if self.__correct_errors: - self.__ptr += 1 - continue - else: - raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2)) - msg_type = self.__buffer[self.__ptr+2] - if msg_type == self.MSG_TYPE_FORMAT: - # parse FORMAT message - if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN: - break - self.__parseMsgDescr() - else: - # parse data message - msg_descr = self.__msg_descrs[msg_type] - if msg_descr == None: - raise Exception("Unknown msg type: %i" % msg_type) - msg_length = msg_descr[0] - if self.__bytesLeft() < msg_length: - break - if first_data_msg: - # build CSV columns and init data map - self.__initCSV() - first_data_msg = False - self.__parseMsg(msg_descr) - bytes_read += self.__ptr - if not self.__debug_out and self.__time_msg != None and self.__csv_updated: - self.__printCSVRow() - f.close() - - def __bytesLeft(self): - return len(self.__buffer) - self.__ptr - - def __filterMsg(self, msg_name): - show_fields = "*" - if len(self.__msg_filter_map) > 0: - show_fields = self.__msg_filter_map.get(msg_name) - return show_fields - - def __initCSV(self): - if len(self.__msg_filter) == 0: - for msg_name in self.__msg_names: - self.__msg_filter.append((msg_name, "*")) - for msg_name, show_fields in self.__msg_filter: - if show_fields == "*": - show_fields = self.__msg_labels.get(msg_name, []) - self.__msg_filter_map[msg_name] = show_fields - for field in show_fields: - full_label = msg_name + "_" + field - self.__csv_columns.append(full_label) - self.__csv_data[full_label] = None - if self.__file != None: - print(self.__csv_delim.join(self.__csv_columns), file=self.__file) - else: - print(self.__csv_delim.join(self.__csv_columns)) - - def __printCSVRow(self): - s = [] - for full_label in self.__csv_columns: - v = self.__csv_data[full_label] - if v == None: - v = self.__csv_null - else: - v = str(v) - s.append(v) - - if self.__file != None: - print(self.__csv_delim.join(s), file=self.__file) - else: - print(self.__csv_delim.join(s)) - - def __parseMsgDescr(self): - if runningPython3: - data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]) - else: - data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])) - msg_type = data[0] - if msg_type != self.MSG_TYPE_FORMAT: - msg_length = data[1] - msg_name = _parseCString(data[2]) - msg_format = _parseCString(data[3]) - msg_labels = _parseCString(data[4]).split(",") - # Convert msg_format to struct.unpack format string - msg_struct = "" - msg_mults = [] - for c in msg_format: - try: - f = self.FORMAT_TO_STRUCT[c] - msg_struct += f[0] - msg_mults.append(f[1]) - except KeyError as e: - raise Exception("Unsupported format char: %s in message %s (%i)" % (c, msg_name, msg_type)) - msg_struct = "<" + msg_struct # force little-endian - self.__msg_descrs[msg_type] = (msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults) - self.__msg_labels[msg_name] = msg_labels - self.__msg_names.append(msg_name) - if self.__debug_out: - if self.__filterMsg(msg_name) != None: - print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % ( - msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)) - self.__ptr += self.MSG_FORMAT_PACKET_LEN - - def __parseMsg(self, msg_descr): - msg_length, msg_name, msg_format, msg_labels, msg_struct, msg_mults = msg_descr - if not self.__debug_out and self.__time_msg != None and msg_name == self.__time_msg and self.__csv_updated: - self.__printCSVRow() - self.__csv_updated = False - show_fields = self.__filterMsg(msg_name) - if (show_fields != None): - if runningPython3: - data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])) - else: - data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))) - for i in range(len(data)): - if type(data[i]) is str: - data[i] = _parseCString(data[i]) - m = msg_mults[i] - if m != None: - data[i] = data[i] * m - if self.__debug_out: - s = [] - for i in range(len(data)): - label = msg_labels[i] - if show_fields == "*" or label in show_fields: - s.append(label + "=" + str(data[i])) - print("MSG %s: %s" % (msg_name, ", ".join(s))) - else: - # update CSV data buffer - for i in range(len(data)): - label = msg_labels[i] - if label in show_fields: - self.__csv_data[msg_name + "_" + label] = data[i] - if self.__time_msg != None and msg_name != self.__time_msg: - self.__csv_updated = True - if self.__time_msg == None: - self.__printCSVRow() - self.__ptr += msg_length - -def _main(): - if len(sys.argv) < 2: - print("Usage: python sdlog2_dump.py [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n") - print("\t-v\tUse plain debug output instead of CSV.\n") - print("\t-e\tRecover from errors.\n") - print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n") - print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n") - print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.") - print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n") - print("\t-fPrint to file instead of stdout") - return - fn = sys.argv[1] - debug_out = False - correct_errors = False - msg_filter = [] - csv_null = "" - csv_delim = "," - time_msg = "TIME" - file_name = None - opt = None - for arg in sys.argv[2:]: - if opt != None: - if opt == "d": - csv_delim = arg - elif opt == "n": - csv_null = arg - elif opt == "t": - time_msg = arg - elif opt == "f": - file_name = arg - elif opt == "m": - show_fields = "*" - a = arg.split("_") - if len(a) > 1: - show_fields = a[1].split(",") - msg_filter.append((a[0], show_fields)) - opt = None - else: - if arg == "-v": - debug_out = True - elif arg == "-e": - correct_errors = True - elif arg == "-d": - opt = "d" - elif arg == "-n": - opt = "n" - elif arg == "-m": - opt = "m" - elif arg == "-t": - opt = "t" - elif arg == "-f": - opt = "f" - - if csv_delim == "\\t": - csv_delim = "\t" - parser = SDLog2Parser() - parser.setCSVDelimiter(csv_delim) - parser.setCSVNull(csv_null) - parser.setMsgFilter(msg_filter) - parser.setTimeMsg(time_msg) - parser.setFileName(file_name) - parser.setDebugOut(debug_out) - parser.setCorrectErrors(correct_errors) - parser.process(fn) - -if __name__ == "__main__": - _main() -- cgit v1.2.3 From a8b3381ca9675890b0d36e98a4453ac18d19df3e Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 17 Feb 2014 21:29:14 +0100 Subject: BL-Ctrl 3.0 fix --- src/drivers/mkblctrl/mkblctrl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index ec5f77d74..705e98eea 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -705,7 +705,7 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C) Motor[i].State |= MOTOR_STATE_PRESENT_MASK; // set present bit; foundMotorCount++; - if (Motor[i].MaxPWM == 250) { + if ((Motor[i].MaxPWM & 252) == 248) { Motor[i].Version = BLCTRL_NEW; } else { -- cgit v1.2.3