forked from Archive/PX4-Autopilot
Merge branch 'master' of github.com:PX4/Firmware into fmuv2_bringup
This commit is contained in:
commit
1543c99003
Binary file not shown.
Binary file not shown.
Before Width: | Height: | Size: 25 KiB |
Binary file not shown.
Binary file not shown.
Before Width: | Height: | Size: 36 KiB |
Binary file not shown.
Binary file not shown.
Binary file not shown.
Before Width: | Height: | Size: 29 KiB |
Binary file not shown.
Binary file not shown.
Before Width: | Height: | Size: 204 KiB |
|
@ -0,0 +1,534 @@
|
|||
% 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 = 'log_second_flight.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);
|
||||
|
||||
disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s)]);
|
||||
|
||||
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<INUSL>
|
||||
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_maxtime<mintime))
|
||||
set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than maxtime! Values were not changed.','BackgroundColor','red');
|
||||
bErr=true;
|
||||
else
|
||||
%2: MinTime must be <=CurTime
|
||||
if(new_mintime>CurTime)
|
||||
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<CurTime)
|
||||
set(h.labels.GUIState,'String','Error: Maxtime cannot be smaller than CurTime! CurTime set to new maxtime.','BackgroundColor','red');
|
||||
maxtime=new_maxtime;
|
||||
CurTime=maxtime;
|
||||
bErr=true;
|
||||
end
|
||||
end
|
||||
|
||||
if(bErr==false)
|
||||
maxtime=new_maxtime;
|
||||
mintime=new_mintime;
|
||||
end
|
||||
|
||||
%Needs to be done in case values were reset above
|
||||
set(h.sliders.MinTime,'Value',mintime);
|
||||
set(h.sliders.MaxTime,'Value',maxtime);
|
||||
|
||||
%Update curtime-slider
|
||||
set(h.sliders.CurTime,'Value',CurTime);
|
||||
set(h.sliders.CurTime,'Max',maxtime);
|
||||
set(h.sliders.CurTime,'Min',mintime);
|
||||
temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min');
|
||||
set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); %Set Stepsize to constant [in seconds]
|
||||
|
||||
%update edit fields
|
||||
set(h.edits.CurTime,'String',get(h.sliders.CurTime,'Value'));
|
||||
set(h.edits.MinTime,'String',get(h.sliders.MinTime,'Value'));
|
||||
set(h.edits.MaxTime,'String',get(h.sliders.MaxTime,'Value'));
|
||||
|
||||
%Finally, we have to redraw. Update time indices first.
|
||||
[imintime,imaxtime]=FindMinMaxTimeIndices();
|
||||
DrawRawData(); %Rawdata only
|
||||
DrawCurrentAircraftState(); %path info & markers
|
||||
end
|
||||
|
||||
|
||||
%% ************************************************************************
|
||||
% CURTIME CALLBACK (nested function)
|
||||
% ************************************************************************
|
||||
function curtime_callback(hObj,event) %#ok<INUSL>
|
||||
%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(temp<maxtime && temp>mintime)
|
||||
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
|
|
@ -55,6 +55,8 @@ class SDLog2Parser:
|
|||
__time_msg = None
|
||||
__debug_out = False
|
||||
__correct_errors = False
|
||||
__file_name = None
|
||||
__file = None
|
||||
|
||||
def __init__(self):
|
||||
return
|
||||
|
@ -87,6 +89,14 @@ class SDLog2Parser:
|
|||
|
||||
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()
|
||||
|
@ -154,10 +164,13 @@ class SDLog2Parser:
|
|||
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
|
||||
full_label = msg_name + "_" + field
|
||||
self.__csv_columns.append(full_label)
|
||||
self.__csv_data[full_label] = None
|
||||
print self.__csv_delim.join(self.__csv_columns)
|
||||
if self.__file != None:
|
||||
print >> self.__file, self.__csv_delim.join(self.__csv_columns)
|
||||
else:
|
||||
print self.__csv_delim.join(self.__csv_columns)
|
||||
|
||||
def __printCSVRow(self):
|
||||
s = []
|
||||
|
@ -168,7 +181,11 @@ class SDLog2Parser:
|
|||
else:
|
||||
v = str(v)
|
||||
s.append(v)
|
||||
print self.__csv_delim.join(s)
|
||||
|
||||
if self.__file != None:
|
||||
print >> self.__file, self.__csv_delim.join(s)
|
||||
else:
|
||||
print self.__csv_delim.join(s)
|
||||
|
||||
def __parseMsgDescr(self):
|
||||
data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])
|
||||
|
@ -224,7 +241,7 @@ class SDLog2Parser:
|
|||
for i in xrange(len(data)):
|
||||
label = msg_labels[i]
|
||||
if label in show_fields:
|
||||
self.__csv_data[msg_name + "." + label] = data[i]
|
||||
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:
|
||||
|
@ -240,6 +257,7 @@ def _main():
|
|||
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
|
||||
|
@ -247,7 +265,8 @@ def _main():
|
|||
msg_filter = []
|
||||
csv_null = ""
|
||||
csv_delim = ","
|
||||
time_msg = None
|
||||
time_msg = "TIME"
|
||||
file_name = None
|
||||
opt = None
|
||||
for arg in sys.argv[2:]:
|
||||
if opt != None:
|
||||
|
@ -257,9 +276,11 @@ def _main():
|
|||
csv_null = arg
|
||||
elif opt == "t":
|
||||
time_msg = arg
|
||||
elif opt == "f":
|
||||
file_name = arg
|
||||
elif opt == "m":
|
||||
show_fields = "*"
|
||||
a = arg.split(".")
|
||||
a = arg.split("_")
|
||||
if len(a) > 1:
|
||||
show_fields = a[1].split(",")
|
||||
msg_filter.append((a[0], show_fields))
|
||||
|
@ -277,6 +298,8 @@ def _main():
|
|||
opt = "m"
|
||||
elif arg == "-t":
|
||||
opt = "t"
|
||||
elif arg == "-f":
|
||||
opt = "f"
|
||||
|
||||
if csv_delim == "\\t":
|
||||
csv_delim = "\t"
|
||||
|
@ -285,6 +308,7 @@ def _main():
|
|||
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)
|
||||
|
|
|
@ -53,6 +53,7 @@ MODULES += systemcmds/pwm
|
|||
MODULES += systemcmds/reboot
|
||||
MODULES += systemcmds/top
|
||||
MODULES += systemcmds/tests
|
||||
MODULES += systemcmds/config
|
||||
|
||||
#
|
||||
# General system control
|
||||
|
|
|
@ -157,6 +157,14 @@ ETSAirspeed::collect()
|
|||
}
|
||||
|
||||
uint16_t diff_pres_pa = val[1] << 8 | val[0];
|
||||
if (diff_pres_pa == 0) {
|
||||
// a zero value means the pressure sensor cannot give us a
|
||||
// value. We need to return, and not report a value or the
|
||||
// caller could end up using this value as part of an
|
||||
// average
|
||||
log("zero value from sensor");
|
||||
return -1;
|
||||
}
|
||||
|
||||
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
|
||||
diff_pres_pa = 0;
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -35,6 +35,9 @@
|
|||
* @file mpu6000.cpp
|
||||
*
|
||||
* Driver for the Invensense MPU6000 connected via SPI.
|
||||
*
|
||||
* @author Andrew Tridgell
|
||||
* @author Pat Hickey
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
@ -191,6 +194,7 @@ private:
|
|||
orb_advert_t _gyro_topic;
|
||||
|
||||
unsigned _reads;
|
||||
unsigned _sample_rate;
|
||||
perf_counter_t _sample_perf;
|
||||
|
||||
/**
|
||||
|
@ -314,6 +318,7 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
|
|||
_gyro_range_rad_s(0.0f),
|
||||
_gyro_topic(-1),
|
||||
_reads(0),
|
||||
_sample_rate(500),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read"))
|
||||
{
|
||||
// disable debug() calls
|
||||
|
@ -366,10 +371,6 @@ MPU6000::init()
|
|||
return ret;
|
||||
}
|
||||
|
||||
/* advertise sensor topics */
|
||||
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report);
|
||||
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report);
|
||||
|
||||
// Chip reset
|
||||
write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
|
||||
up_udelay(10000);
|
||||
|
@ -384,7 +385,7 @@ MPU6000::init()
|
|||
|
||||
// SAMPLE RATE
|
||||
//write_reg(MPUREG_SMPLRT_DIV, 0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz
|
||||
_set_sample_rate(200); // default sample rate = 200Hz
|
||||
_set_sample_rate(_sample_rate); // default sample rate = 200Hz
|
||||
usleep(1000);
|
||||
|
||||
// FS & DLPF FS=2000 deg/s, DLPF = 20Hz (low pass filter)
|
||||
|
@ -463,10 +464,18 @@ MPU6000::init()
|
|||
/* do CDev init for the gyro device node, keep it optional */
|
||||
int gyro_ret = _gyro->init();
|
||||
|
||||
/* ensure we got real values to share */
|
||||
measure();
|
||||
|
||||
if (gyro_ret != OK) {
|
||||
_gyro_topic = -1;
|
||||
} else {
|
||||
_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &_gyro_report);
|
||||
}
|
||||
|
||||
/* advertise sensor topics */
|
||||
_accel_topic = orb_advertise(ORB_ID(sensor_accel), &_accel_report);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
@ -509,6 +518,7 @@ MPU6000::_set_sample_rate(uint16_t desired_sample_rate_hz)
|
|||
if(div>200) div=200;
|
||||
if(div<1) div=1;
|
||||
write_reg(MPUREG_SMPLRT_DIV, div-1);
|
||||
_sample_rate = 1000 / div;
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -660,8 +670,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return -EINVAL;
|
||||
|
||||
|
||||
case ACCELIOCSSAMPLERATE:
|
||||
case ACCELIOCGSAMPLERATE:
|
||||
return _sample_rate;
|
||||
|
||||
case ACCELIOCSSAMPLERATE:
|
||||
_set_sample_rate(arg);
|
||||
return OK;
|
||||
|
||||
|
@ -689,12 +701,13 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return OK;
|
||||
|
||||
case ACCELIOCSRANGE:
|
||||
case ACCELIOCGRANGE:
|
||||
/* XXX not implemented */
|
||||
// XXX change these two values on set:
|
||||
// _accel_range_scale = (9.81f / 4096.0f);
|
||||
// _accel_range_rad_s = 8.0f * 9.81f;
|
||||
// _accel_range_m_s2 = 8.0f * 9.81f;
|
||||
return -EINVAL;
|
||||
case ACCELIOCGRANGE:
|
||||
return _accel_range_m_s2;
|
||||
|
||||
case ACCELIOCSELFTEST:
|
||||
return self_test();
|
||||
|
@ -718,10 +731,12 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
case SENSORIOCRESET:
|
||||
return ioctl(filp, cmd, arg);
|
||||
|
||||
case GYROIOCSSAMPLERATE:
|
||||
case GYROIOCGSAMPLERATE:
|
||||
_set_sample_rate(arg);
|
||||
return OK;
|
||||
return _sample_rate;
|
||||
|
||||
case GYROIOCSSAMPLERATE:
|
||||
_set_sample_rate(arg);
|
||||
return OK;
|
||||
|
||||
case GYROIOCSLOWPASS:
|
||||
case GYROIOCGLOWPASS:
|
||||
|
@ -739,12 +754,13 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
|
|||
return OK;
|
||||
|
||||
case GYROIOCSRANGE:
|
||||
case GYROIOCGRANGE:
|
||||
/* XXX not implemented */
|
||||
// XXX change these two values on set:
|
||||
// _gyro_range_scale = xx
|
||||
// _gyro_range_m_s2 = xx
|
||||
// _gyro_range_rad_s = xx
|
||||
return -EINVAL;
|
||||
case GYROIOCGRANGE:
|
||||
return _gyro_range_rad_s;
|
||||
|
||||
case GYROIOCSELFTEST:
|
||||
return self_test();
|
||||
|
|
|
@ -587,6 +587,8 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
|
|||
|
||||
close(fd);
|
||||
|
||||
int errcount = 0;
|
||||
|
||||
while (calibration_counter < calibration_count) {
|
||||
|
||||
/* wait blocking for new data */
|
||||
|
@ -602,8 +604,12 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status)
|
|||
calibration_counter++;
|
||||
|
||||
} else if (poll_ret == 0) {
|
||||
/* any poll failure for 1s is a reason to abort */
|
||||
mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
|
||||
errcount++;
|
||||
}
|
||||
|
||||
if (errcount > 1000) {
|
||||
/* any persisting poll error is a reason to abort */
|
||||
mavlink_log_info(mavlink_fd, "permanent gyro error, aborted.");
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -0,0 +1,200 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file config.c
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* config tool.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include <drivers/drv_gyro.h>
|
||||
#include <drivers/drv_accel.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
|
||||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/err.h"
|
||||
|
||||
__EXPORT int config_main(int argc, char *argv[]);
|
||||
|
||||
static void do_gyro(int argc, char *argv[]);
|
||||
static void do_accel(int argc, char *argv[]);
|
||||
static void do_mag(int argc, char *argv[]);
|
||||
|
||||
int
|
||||
config_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc >= 2) {
|
||||
if (!strcmp(argv[1], "gyro")) {
|
||||
if (argc >= 3) {
|
||||
do_gyro(argc - 2, argv + 2);
|
||||
} else {
|
||||
errx(1, "not enough parameters.");
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "accel")) {
|
||||
if (argc >= 3) {
|
||||
do_accel(argc - 2, argv + 2);
|
||||
} else {
|
||||
errx(1, "not enough parameters.");
|
||||
}
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "mag")) {
|
||||
if (argc >= 3) {
|
||||
do_mag(argc - 2, argv + 2);
|
||||
} else {
|
||||
errx(1, "not enough parameters.");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
errx(1, "expected a command, try 'gyro', 'accel', 'mag'");
|
||||
}
|
||||
|
||||
static void
|
||||
do_gyro(int argc, char *argv[])
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open(GYRO_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("%s", GYRO_DEVICE_PATH);
|
||||
errx(1, "FATAL: no gyro found");
|
||||
|
||||
} else {
|
||||
|
||||
if (argc >= 2) {
|
||||
|
||||
char* end;
|
||||
int i = strtol(argv[1],&end,10);
|
||||
|
||||
if (!strcmp(argv[0], "sampling")) {
|
||||
|
||||
/* set the accel internal sampling rate up to at leat i Hz */
|
||||
ioctl(fd, GYROIOCSSAMPLERATE, i);
|
||||
|
||||
} else if (!strcmp(argv[0], "rate")) {
|
||||
|
||||
/* set the driver to poll at i Hz */
|
||||
ioctl(fd, SENSORIOCSPOLLRATE, i);
|
||||
} else if (!strcmp(argv[0], "range")) {
|
||||
|
||||
/* set the range to i dps */
|
||||
ioctl(fd, GYROIOCSRANGE, i);
|
||||
}
|
||||
|
||||
} else if (!(argc > 0 && !strcmp(argv[0], "info"))) {
|
||||
warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2000' to set measurement range to 2000 dps\n\t");
|
||||
}
|
||||
|
||||
int srate = ioctl(fd, GYROIOCGSAMPLERATE, 0);
|
||||
int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0);
|
||||
int range = ioctl(fd, GYROIOCGRANGE, 0);
|
||||
|
||||
warnx("gyro: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d dps", srate, prate, range);
|
||||
|
||||
close(fd);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
do_mag(int argc, char *argv[])
|
||||
{
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
do_accel(int argc, char *argv[])
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open(ACCEL_DEVICE_PATH, 0);
|
||||
|
||||
if (fd < 0) {
|
||||
warn("%s", ACCEL_DEVICE_PATH);
|
||||
errx(1, "FATAL: no accelerometer found");
|
||||
|
||||
} else {
|
||||
|
||||
if (argc >= 2) {
|
||||
|
||||
char* end;
|
||||
int i = strtol(argv[1],&end,10);
|
||||
|
||||
if (!strcmp(argv[0], "sampling")) {
|
||||
|
||||
/* set the accel internal sampling rate up to at leat i Hz */
|
||||
ioctl(fd, ACCELIOCSSAMPLERATE, i);
|
||||
|
||||
} else if (!strcmp(argv[0], "rate")) {
|
||||
|
||||
/* set the driver to poll at i Hz */
|
||||
ioctl(fd, SENSORIOCSPOLLRATE, i);
|
||||
} else if (!strcmp(argv[0], "range")) {
|
||||
|
||||
/* set the range to i dps */
|
||||
ioctl(fd, ACCELIOCSRANGE, i);
|
||||
}
|
||||
} else if (!(argc > 0 && !strcmp(argv[0], "info"))) {
|
||||
warnx("no arguments given. Try: \n\n\t'sampling 500' to set sampling to 500 Hz\n\t'rate 500' to set publication rate to 500 Hz\n\t'range 2' to set measurement range to 2 G\n\t");
|
||||
}
|
||||
|
||||
int srate = ioctl(fd, ACCELIOCGSAMPLERATE, 0);
|
||||
int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0);
|
||||
int range = ioctl(fd, ACCELIOCGRANGE, 0);
|
||||
|
||||
warnx("accel: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d m/s", srate, prate, range);
|
||||
|
||||
close(fd);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
|
@ -0,0 +1,44 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build the config tool.
|
||||
#
|
||||
|
||||
MODULE_COMMAND = config
|
||||
SRCS = config.c
|
||||
|
||||
MODULE_STACKSIZE = 4096
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
Loading…
Reference in New Issue