aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJames Goppert <james.goppert@gmail.com>2013-08-03 12:18:41 -0400
committerJames Goppert <james.goppert@gmail.com>2013-08-03 12:18:41 -0400
commit8f1487b1570ddd79bbd027d3a1bed0c712d2871b (patch)
tree7293f01a368aed8d539dac99b051e5e562952a02
parenta569cd834c13052ef3210ab9b8c1afd03b81fef6 (diff)
parent24c43ad62d03fdfc0a13b5e6fae22c29bbc827c3 (diff)
downloadpx4-firmware-8f1487b1570ddd79bbd027d3a1bed0c712d2871b.tar.gz
px4-firmware-8f1487b1570ddd79bbd027d3a1bed0c712d2871b.tar.bz2
px4-firmware-8f1487b1570ddd79bbd027d3a1bed0c712d2871b.zip
Merge branch 'master' of github.com:jgoppert/Firmware into md25_dev
-rw-r--r--Documentation/commander_app.odgbin11628 -> 0 bytes
-rw-r--r--Documentation/commander_app.pngbin25356 -> 0 bytes
-rw-r--r--Documentation/flight_mode_state_machine.odgbin18105 -> 18452 bytes
-rw-r--r--Documentation/position_control.odgbin12559 -> 0 bytes
-rw-r--r--Documentation/position_control.pngbin36561 -> 0 bytes
-rw-r--r--Documentation/position_estimator_app.odgbin12160 -> 0 bytes
-rw-r--r--Documentation/position_estimator_app.pdfbin14243 -> 0 bytes
-rw-r--r--Documentation/position_estimator_app.pngbin29623 -> 0 bytes
-rw-r--r--Documentation/state_machine.odgbin18576 -> 0 bytes
-rw-r--r--Documentation/state_machine.pngbin208880 -> 0 bytes
-rw-r--r--ROMFS/px4fmu_common/init.d/02_io_quad_x22
-rw-r--r--ROMFS/px4fmu_common/init.d/10_io_f33037
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.sensors4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb49
-rwxr-xr-xROMFS/px4fmu_common/init.d/rcS23
-rw-r--r--Tools/logconv.m534
-rw-r--r--Tools/sdlog2_dump.py36
-rw-r--r--makefiles/config_px4fmu-v1_default.mk4
-rw-r--r--src/drivers/airspeed/airspeed.cpp378
-rw-r--r--src/drivers/airspeed/airspeed.h169
-rw-r--r--src/drivers/airspeed/module.mk38
-rw-r--r--src/drivers/drv_airspeed.h9
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp398
-rw-r--r--src/drivers/ets_airspeed/module.mk2
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp506
-rw-r--r--src/drivers/meas_airspeed/module.mk41
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp44
-rw-r--r--src/modules/commander/accelerometer_calibration.c4
-rw-r--r--src/modules/commander/commander.c10
-rw-r--r--src/modules/sensors/sensor_params.c2
-rw-r--r--src/modules/sensors/sensors.cpp64
-rw-r--r--src/systemcmds/config/config.c200
-rw-r--r--src/systemcmds/config/module.mk44
-rw-r--r--src/systemcmds/ramtron/module.mk6
-rw-r--r--src/systemcmds/ramtron/ramtron.c279
35 files changed, 2393 insertions, 510 deletions
diff --git a/Documentation/commander_app.odg b/Documentation/commander_app.odg
deleted file mode 100644
index 17459f7cf..000000000
--- a/Documentation/commander_app.odg
+++ /dev/null
Binary files differ
diff --git a/Documentation/commander_app.png b/Documentation/commander_app.png
deleted file mode 100644
index 6503817da..000000000
--- a/Documentation/commander_app.png
+++ /dev/null
Binary files differ
diff --git a/Documentation/flight_mode_state_machine.odg b/Documentation/flight_mode_state_machine.odg
index b630ecb40..f9fa7a032 100644
--- a/Documentation/flight_mode_state_machine.odg
+++ b/Documentation/flight_mode_state_machine.odg
Binary files differ
diff --git a/Documentation/position_control.odg b/Documentation/position_control.odg
deleted file mode 100644
index 5fb002c5e..000000000
--- a/Documentation/position_control.odg
+++ /dev/null
Binary files differ
diff --git a/Documentation/position_control.png b/Documentation/position_control.png
deleted file mode 100644
index d8d1a8b0c..000000000
--- a/Documentation/position_control.png
+++ /dev/null
Binary files differ
diff --git a/Documentation/position_estimator_app.odg b/Documentation/position_estimator_app.odg
deleted file mode 100644
index a6fc67373..000000000
--- a/Documentation/position_estimator_app.odg
+++ /dev/null
Binary files differ
diff --git a/Documentation/position_estimator_app.pdf b/Documentation/position_estimator_app.pdf
deleted file mode 100644
index bc07209ee..000000000
--- a/Documentation/position_estimator_app.pdf
+++ /dev/null
Binary files differ
diff --git a/Documentation/position_estimator_app.png b/Documentation/position_estimator_app.png
deleted file mode 100644
index 377549f63..000000000
--- a/Documentation/position_estimator_app.png
+++ /dev/null
Binary files differ
diff --git a/Documentation/state_machine.odg b/Documentation/state_machine.odg
deleted file mode 100644
index 2f55a13dd..000000000
--- a/Documentation/state_machine.odg
+++ /dev/null
Binary files differ
diff --git a/Documentation/state_machine.png b/Documentation/state_machine.png
deleted file mode 100644
index 4daeddfc9..000000000
--- a/Documentation/state_machine.png
+++ /dev/null
Binary files differ
diff --git a/ROMFS/px4fmu_common/init.d/02_io_quad_x b/ROMFS/px4fmu_common/init.d/02_io_quad_x
index 131abf8c4..c63e92f6d 100644
--- a/ROMFS/px4fmu_common/init.d/02_io_quad_x
+++ b/ROMFS/px4fmu_common/init.d/02_io_quad_x
@@ -40,28 +40,6 @@ fi
param set MAV_TYPE 2
#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io.bin"
- if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
- then
- cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
- echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
- else
- echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
- echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
- fi
- fi
-fi
-
-#
# Start MAVLink (depends on orb)
#
mavlink start -d /dev/ttyS1 -b 57600
diff --git a/ROMFS/px4fmu_common/init.d/10_io_f330 b/ROMFS/px4fmu_common/init.d/10_io_f330
index 4107fab4f..4450eb50d 100644
--- a/ROMFS/px4fmu_common/init.d/10_io_f330
+++ b/ROMFS/px4fmu_common/init.d/10_io_f330
@@ -15,20 +15,19 @@ then
# Set all params here, then disable autoconfig
param set SYS_AUTOCONFIG 0
- param set MC_ATTRATE_D 0.007
+ param set MC_ATTRATE_D 0.005
param set MC_ATTRATE_I 0.0
- param set MC_ATTRATE_P 0.13
+ param set MC_ATTRATE_P 0.1
param set MC_ATT_D 0.0
param set MC_ATT_I 0.0
- param set MC_ATT_P 7.0
- param set MC_POS_P 0.1
+ param set MC_ATT_P 4.5
param set MC_RCLOSS_THR 0.0
param set MC_YAWPOS_D 0.0
- param set MC_YAWPOS_I 0.5
- param set MC_YAWPOS_P 1.0
+ param set MC_YAWPOS_I 0.3
+ param set MC_YAWPOS_P 0.6
param set MC_YAWRATE_D 0.0
param set MC_YAWRATE_I 0.0
- param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_P 0.1
param save /fs/microsd/params
fi
@@ -41,28 +40,6 @@ fi
param set MAV_TYPE 2
#
-# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
-#
-if [ -f /fs/microsd/px4io2.bin ]
-then
- echo "PX4IO Firmware found. Checking Upgrade.."
- if cmp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur
- then
- echo "No newer version, skipping upgrade."
- else
- echo "Loading /fs/microsd/px4io2.bin"
- if px4io update /fs/microsd/px4io2.bin > /fs/microsd/px4io2.log
- then
- cp /fs/microsd/px4io2.bin /fs/microsd/px4io2.cur
- echo "Flashed /fs/microsd/px4io2.bin OK" >> /fs/microsd/px4io2.log
- else
- echo "Failed flashing /fs/microsd/px4io2.bin" >> /fs/microsd/px4io2.log
- echo "Failed to upgrade PX4IO2 firmware - check if PX4IO2 is in bootloader mode"
- fi
- fi
-fi
-
-#
# Start MAVLink (depends on orb)
#
mavlink start
@@ -128,7 +105,7 @@ multirotor_att_control start
#
# Start logging
#
-sdlog2 start -r 20 -a -b 14
+sdlog2 start -r 20 -a -b 16
#
# Start system state
diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors
index 73f40c503..5e80ddc2f 100644
--- a/ROMFS/px4fmu_common/init.d/rc.sensors
+++ b/ROMFS/px4fmu_common/init.d/rc.sensors
@@ -25,7 +25,7 @@ then
else
echo "using L3GD20 and LSM303D"
l3gd20 start
- lsm303 start
+ lsm303d start
fi
#
@@ -40,4 +40,4 @@ then
# Check sensors - run AFTER 'sensors start'
#
preflight_check &
-fi \ No newline at end of file
+fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index c89932bb5..5b1bd272e 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -13,35 +13,46 @@ if mavlink stop
then
echo "stopped other MAVLink instance"
fi
+sleep 2
mavlink start -b 230400 -d /dev/ttyACM0
-if [ $MODE == autostart ]
+# Start the commander
+if commander start
then
+ echo "Commander started"
+fi
- # Start the commander
- commander start
+# Start px4io if present
+if px4io start
+then
+ echo "PX4IO driver started"
+else
+ if fmu mode_serial
+ then
+ echo "FMU driver started"
+ fi
+fi
- # Start sensors
- sh /etc/init.d/rc.sensors
+# Start sensors
+sh /etc/init.d/rc.sensors
- # Start one of the estimators
- if attitude_estimator_ekf status
+# Start one of the estimators
+if attitude_estimator_ekf status
+then
+ echo "multicopter att filter running"
+else
+ if att_pos_estimator_ekf status
then
- echo "multicopter att filter running"
+ echo "fixedwing att filter running"
else
- if att_pos_estimator_ekf status
- then
- echo "fixedwing att filter running"
- else
- attitude_estimator_ekf start
- fi
+ attitude_estimator_ekf start
fi
+fi
- # Start GPS
- if gps start
- then
- echo "GPS started"
- fi
+# Start GPS
+if gps start
+then
+ echo "GPS started"
fi
echo "MAVLink started, exiting shell.."
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index b22591f3c..f0ee1a0c6 100755
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -81,6 +81,26 @@ else
fi
fi
+#
+# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
+#
+if [ -f /fs/microsd/px4io.bin ]
+then
+ echo "PX4IO Firmware found. Checking Upgrade.."
+ if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
+ then
+ echo "No newer version, skipping upgrade."
+ else
+ echo "Loading /fs/microsd/px4io.bin"
+ if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io.log
+ then
+ cp /fs/microsd/px4io.bin /fs/microsd/px4io.cur
+ echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io.log
+ else
+ echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io.log
+ echo "Failed to upgrade px4io firmware - check if px4io is in bootloader mode"
+ fi
+ fi
fi
#
@@ -121,3 +141,6 @@ if param compare SYS_AUTOSTART 31
then
sh /etc/init.d/31_io_phantom
fi
+
+# End of autostart
+fi
diff --git a/Tools/logconv.m b/Tools/logconv.m
new file mode 100644
index 000000000..f7c291b48
--- /dev/null
+++ b/Tools/logconv.m
@@ -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
diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py
index 318f72971..ebc04f4d0 100644
--- a/Tools/sdlog2_dump.py
+++ b/Tools/sdlog2_dump.py
@@ -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)
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index cbca4f6a6..4d23e7c27 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -32,13 +32,16 @@ MODULES += drivers/hott/hott_sensors
MODULES += drivers/blinkm
MODULES += drivers/mkblctrl
MODULES += drivers/md25
+MODULES += drivers/airspeed
MODULES += drivers/ets_airspeed
+MODULES += drivers/meas_airspeed
MODULES += modules/sensors
#
# System commands
#
MODULES += systemcmds/eeprom
+MODULES += systemcmds/ramtron
MODULES += systemcmds/bl_update
MODULES += systemcmds/boardinfo
MODULES += systemcmds/i2c
@@ -50,6 +53,7 @@ MODULES += systemcmds/pwm
MODULES += systemcmds/reboot
MODULES += systemcmds/top
MODULES += systemcmds/tests
+MODULES += systemcmds/config
#
# General system control
diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp
new file mode 100644
index 000000000..5a8157deb
--- /dev/null
+++ b/src/drivers/airspeed/airspeed.cpp
@@ -0,0 +1,378 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file ets_airspeed.cpp
+ * @author Simon Wilks
+ *
+ * Driver for the Eagle Tree Airspeed V3 connected via I2C.
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <arch/board/board.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <drivers/airspeed/airspeed.h>
+
+Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) :
+ I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000),
+ _num_reports(0),
+ _next_report(0),
+ _oldest_report(0),
+ _reports(nullptr),
+ _sensor_ok(false),
+ _measure_ticks(0),
+ _collect_phase(false),
+ _diff_pres_offset(0.0f),
+ _airspeed_pub(-1),
+ _conversion_interval(conversion_interval),
+ _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")),
+ _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors")),
+ _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows"))
+{
+ // enable debug() calls
+ _debug_enabled = true;
+
+ // work_cancel in the dtor will explode if we don't do this...
+ memset(&_work, 0, sizeof(_work));
+}
+
+Airspeed::~Airspeed()
+{
+ /* make sure we are truly inactive */
+ stop();
+
+ /* free any existing reports */
+ if (_reports != nullptr)
+ delete[] _reports;
+}
+
+int
+Airspeed::init()
+{
+ int ret = ERROR;
+
+ /* do I2C init (and probe) first */
+ if (I2C::init() != OK)
+ goto out;
+
+ /* allocate basic report buffers */
+ _num_reports = 2;
+ _reports = new struct differential_pressure_s[_num_reports];
+
+ for (unsigned i = 0; i < _num_reports; i++)
+ _reports[i].max_differential_pressure_pa = 0;
+
+ if (_reports == nullptr)
+ goto out;
+
+ _oldest_report = _next_report = 0;
+
+ /* get a publish handle on the airspeed topic */
+ memset(&_reports[0], 0, sizeof(_reports[0]));
+ _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]);
+
+ if (_airspeed_pub < 0)
+ warnx("failed to create airspeed sensor object. Did you start uOrb?");
+
+ ret = OK;
+ /* sensor is ok, but we don't really know if it is within range */
+ _sensor_ok = true;
+out:
+ return ret;
+}
+
+int
+Airspeed::probe()
+{
+ return measure();
+}
+
+int
+Airspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ switch (cmd) {
+
+ case SENSORIOCSPOLLRATE: {
+ switch (arg) {
+
+ /* switching to manual polling */
+ case SENSOR_POLLRATE_MANUAL:
+ stop();
+ _measure_ticks = 0;
+ return OK;
+
+ /* external signalling (DRDY) not supported */
+ case SENSOR_POLLRATE_EXTERNAL:
+
+ /* zero would be bad */
+ case 0:
+ return -EINVAL;
+
+ /* set default/max polling rate */
+ case SENSOR_POLLRATE_MAX:
+ case SENSOR_POLLRATE_DEFAULT: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* set interval for next measurement to minimum legal value */
+ _measure_ticks = USEC2TICK(_conversion_interval);
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+
+ /* adjust to a legal polling interval in Hz */
+ default: {
+ /* do we need to start internal polling? */
+ bool want_start = (_measure_ticks == 0);
+
+ /* convert hz to tick interval via microseconds */
+ unsigned ticks = USEC2TICK(1000000 / arg);
+
+ /* check against maximum rate */
+ if (ticks < USEC2TICK(_conversion_interval))
+ return -EINVAL;
+
+ /* update interval for next measurement */
+ _measure_ticks = ticks;
+
+ /* if we need to start the poll state machine, do it */
+ if (want_start)
+ start();
+
+ return OK;
+ }
+ }
+ }
+
+ case SENSORIOCGPOLLRATE:
+ if (_measure_ticks == 0)
+ return SENSOR_POLLRATE_MANUAL;
+
+ return (1000 / _measure_ticks);
+
+ case SENSORIOCSQUEUEDEPTH: {
+ /* add one to account for the sentinel in the ring */
+ arg++;
+
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 2) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ struct differential_pressure_s *buf = new struct differential_pressure_s[arg];
+
+ if (nullptr == buf)
+ return -ENOMEM;
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete[] _reports;
+ _num_reports = arg;
+ _reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _num_reports - 1;
+
+ case SENSORIOCRESET:
+ /* XXX implement this */
+ return -EINVAL;
+
+ case AIRSPEEDIOCSSCALE: {
+ struct airspeed_scale *s = (struct airspeed_scale*)arg;
+ _diff_pres_offset = s->offset_pa;
+ return OK;
+ }
+
+ case AIRSPEEDIOCGSCALE: {
+ struct airspeed_scale *s = (struct airspeed_scale*)arg;
+ s->offset_pa = _diff_pres_offset;
+ s->scale = 1.0f;
+ return OK;
+ }
+
+ default:
+ /* give it to the superclass */
+ return I2C::ioctl(filp, cmd, arg);
+ }
+}
+
+ssize_t
+Airspeed::read(struct file *filp, char *buffer, size_t buflen)
+{
+ unsigned count = buflen / sizeof(struct differential_pressure_s);
+ int ret = 0;
+
+ /* buffer must be large enough */
+ if (count < 1)
+ return -ENOSPC;
+
+ /* if automatic measurement is enabled */
+ if (_measure_ticks > 0) {
+
+ /*
+ * While there is space in the caller's buffer, and reports, copy them.
+ * Note that we may be pre-empted by the workq thread while we are doing this;
+ * we are careful to avoid racing with them.
+ */
+ while (count--) {
+ if (_oldest_report != _next_report) {
+ memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
+ ret += sizeof(_reports[0]);
+ INCREMENT(_oldest_report, _num_reports);
+ }
+ }
+
+ /* if there was no data, warn the caller */
+ return ret ? ret : -EAGAIN;
+ }
+
+ /* manual measurement - run one conversion */
+ /* XXX really it'd be nice to lock against other readers here */
+ do {
+ _oldest_report = _next_report = 0;
+
+ /* trigger a measurement */
+ if (OK != measure()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* wait for it to complete */
+ usleep(_conversion_interval);
+
+ /* run the collection phase */
+ if (OK != collect()) {
+ ret = -EIO;
+ break;
+ }
+
+ /* state machine will have generated a report, copy it out */
+ memcpy(buffer, _reports, sizeof(*_reports));
+ ret = sizeof(*_reports);
+
+ } while (0);
+
+ return ret;
+}
+
+void
+Airspeed::start()
+{
+ /* reset the report ring and state machine */
+ _collect_phase = false;
+ _oldest_report = _next_report = 0;
+
+ /* schedule a cycle to start things */
+ work_queue(HPWORK, &_work, (worker_t)&Airspeed::cycle_trampoline, this, 1);
+
+ /* notify about state change */
+ struct subsystem_info_s info = {
+ true,
+ true,
+ true,
+ SUBSYSTEM_TYPE_DIFFPRESSURE
+ };
+ static orb_advert_t pub = -1;
+
+ if (pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), pub, &info);
+
+ } else {
+ pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ }
+}
+
+void
+Airspeed::stop()
+{
+ work_cancel(HPWORK, &_work);
+}
+
+void
+Airspeed::cycle_trampoline(void *arg)
+{
+ Airspeed *dev = (Airspeed *)arg;
+
+ dev->cycle();
+}
+
+void
+Airspeed::print_info()
+{
+ perf_print_counter(_sample_perf);
+ perf_print_counter(_comms_errors);
+ perf_print_counter(_buffer_overflows);
+ warnx("poll interval: %u ticks", _measure_ticks);
+ warnx("report queue: %u (%u/%u @ %p)",
+ _num_reports, _oldest_report, _next_report, _reports);
+}
diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h
new file mode 100644
index 000000000..89dfb22d7
--- /dev/null
+++ b/src/drivers/airspeed/airspeed.h
@@ -0,0 +1,169 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file airspeed.h
+ * @author Simon Wilks
+ *
+ * Generic driver for airspeed sensors connected via I2C.
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <arch/board/board.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+/* Default I2C bus */
+#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
+
+/* Oddly, ERROR is not defined for C++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+#ifndef CONFIG_SCHED_WORKQUEUE
+# error This requires CONFIG_SCHED_WORKQUEUE.
+#endif
+
+class __EXPORT Airspeed : public device::I2C
+{
+public:
+ Airspeed(int bus, int address, unsigned conversion_interval);
+ virtual ~Airspeed();
+
+ virtual int init();
+
+ virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+
+ /**
+ * Diagnostics - print some basic information about the driver.
+ */
+ virtual void print_info();
+
+protected:
+ virtual int probe();
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ virtual void cycle() = 0;
+ virtual int measure() = 0;
+ virtual int collect() = 0;
+
+ work_s _work;
+ unsigned _num_reports;
+ volatile unsigned _next_report;
+ volatile unsigned _oldest_report;
+ differential_pressure_s *_reports;
+ bool _sensor_ok;
+ int _measure_ticks;
+ bool _collect_phase;
+ float _diff_pres_offset;
+
+ orb_advert_t _airspeed_pub;
+
+ unsigned _conversion_interval;
+
+ perf_counter_t _sample_perf;
+ perf_counter_t _comms_errors;
+ perf_counter_t _buffer_overflows;
+
+
+ /**
+ * Test whether the device supported by the driver is present at a
+ * specific address.
+ *
+ * @param address The I2C bus address to probe.
+ * @return True if the device is present.
+ */
+ int probe_address(uint8_t address);
+
+ /**
+ * Initialise the automatic measurement state machine and start it.
+ *
+ * @note This function is called at open and error time. It might make sense
+ * to make it more aggressive about resetting the bus in case of errors.
+ */
+ void start();
+
+ /**
+ * Stop the automatic measurement state machine.
+ */
+ void stop();
+
+ /**
+ * Static trampoline from the workq context; because we don't have a
+ * generic workq wrapper yet.
+ *
+ * @param arg Instance pointer for the driver that is polling.
+ */
+ static void cycle_trampoline(void *arg);
+
+};
+
+/* helper macro for handling report buffer indices */
+#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
+
diff --git a/src/drivers/airspeed/module.mk b/src/drivers/airspeed/module.mk
new file mode 100644
index 000000000..4eef06161
--- /dev/null
+++ b/src/drivers/airspeed/module.mk
@@ -0,0 +1,38 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Makefile to build the generic airspeed driver.
+#
+
+SRCS = airspeed.cpp
diff --git a/src/drivers/drv_airspeed.h b/src/drivers/drv_airspeed.h
index bffc35c62..7bb9ee2af 100644
--- a/src/drivers/drv_airspeed.h
+++ b/src/drivers/drv_airspeed.h
@@ -57,5 +57,14 @@
#define _AIRSPEEDIOCBASE (0x7700)
#define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n))
+#define AIRSPEEDIOCSSCALE __AIRSPEEDIOC(0)
+#define AIRSPEEDIOCGSCALE __AIRSPEEDIOC(1)
+
+
+/** airspeed scaling factors; out = (in * Vscale) + offset */
+struct airspeed_scale {
+ float offset_pa;
+ float scale;
+};
#endif /* _DRV_AIRSPEED_H */
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index b34d3fa5d..de8028b0f 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -72,9 +72,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/subsystem_info.h>
-
-/* Default I2C bus */
-#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION
+#include <drivers/airspeed/airspeed.h>
/* I2C bus address */
#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */
@@ -91,336 +89,32 @@
/* Measurement rate is 100Hz */
#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
-/* Oddly, ERROR is not defined for C++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
-
-#ifndef CONFIG_SCHED_WORKQUEUE
-# error This requires CONFIG_SCHED_WORKQUEUE.
-#endif
-
-class ETSAirspeed : public device::I2C
+class ETSAirspeed : public Airspeed
{
public:
ETSAirspeed(int bus, int address = I2C_ADDRESS);
- virtual ~ETSAirspeed();
-
- virtual int init();
-
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
- /**
- * Diagnostics - print some basic information about the driver.
- */
- void print_info();
protected:
- virtual int probe();
-
-private:
- work_s _work;
- unsigned _num_reports;
- volatile unsigned _next_report;
- volatile unsigned _oldest_report;
- differential_pressure_s *_reports;
- bool _sensor_ok;
- int _measure_ticks;
- bool _collect_phase;
- int _diff_pres_offset;
-
- orb_advert_t _airspeed_pub;
-
- perf_counter_t _sample_perf;
- perf_counter_t _comms_errors;
- perf_counter_t _buffer_overflows;
-
-
- /**
- * Test whether the device supported by the driver is present at a
- * specific address.
- *
- * @param address The I2C bus address to probe.
- * @return True if the device is present.
- */
- int probe_address(uint8_t address);
-
- /**
- * Initialise the automatic measurement state machine and start it.
- *
- * @note This function is called at open and error time. It might make sense
- * to make it more aggressive about resetting the bus in case of errors.
- */
- void start();
-
- /**
- * Stop the automatic measurement state machine.
- */
- void stop();
/**
* Perform a poll cycle; collect from the previous measurement
* and start a new one.
*/
- void cycle();
- int measure();
- int collect();
-
- /**
- * Static trampoline from the workq context; because we don't have a
- * generic workq wrapper yet.
- *
- * @param arg Instance pointer for the driver that is polling.
- */
- static void cycle_trampoline(void *arg);
-
+ virtual void cycle();
+ virtual int measure();
+ virtual int collect();
};
-/* helper macro for handling report buffer indices */
-#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0)
-
/*
* Driver 'main' command.
*/
extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]);
-ETSAirspeed::ETSAirspeed(int bus, int address) :
- I2C("ETSAirspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000),
- _num_reports(0),
- _next_report(0),
- _oldest_report(0),
- _reports(nullptr),
- _sensor_ok(false),
- _measure_ticks(0),
- _collect_phase(false),
- _diff_pres_offset(0),
- _airspeed_pub(-1),
- _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")),
- _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")),
- _buffer_overflows(perf_alloc(PC_COUNT, "ets_airspeed_buffer_overflows"))
-{
- // enable debug() calls
- _debug_enabled = true;
-
- // work_cancel in the dtor will explode if we don't do this...
- memset(&_work, 0, sizeof(_work));
-}
-
-ETSAirspeed::~ETSAirspeed()
-{
- /* make sure we are truly inactive */
- stop();
-
- /* free any existing reports */
- if (_reports != nullptr)
- delete[] _reports;
-}
-
-int
-ETSAirspeed::init()
-{
- int ret = ERROR;
-
- /* do I2C init (and probe) first */
- if (I2C::init() != OK)
- goto out;
-
- /* allocate basic report buffers */
- _num_reports = 2;
- _reports = new struct differential_pressure_s[_num_reports];
-
- for (unsigned i = 0; i < _num_reports; i++)
- _reports[i].max_differential_pressure_pa = 0;
-
- if (_reports == nullptr)
- goto out;
-
- _oldest_report = _next_report = 0;
-
- /* get a publish handle on the airspeed topic */
- memset(&_reports[0], 0, sizeof(_reports[0]));
- _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]);
-
- if (_airspeed_pub < 0)
- debug("failed to create airspeed sensor object. Did you start uOrb?");
-
- ret = OK;
- /* sensor is ok, but we don't really know if it is within range */
- _sensor_ok = true;
-out:
- return ret;
-}
-
-int
-ETSAirspeed::probe()
-{
- return measure();
-}
-
-int
-ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- switch (cmd) {
-
- case SENSORIOCSPOLLRATE: {
- switch (arg) {
-
- /* switching to manual polling */
- case SENSOR_POLLRATE_MANUAL:
- stop();
- _measure_ticks = 0;
- return OK;
-
- /* external signalling (DRDY) not supported */
- case SENSOR_POLLRATE_EXTERNAL:
-
- /* zero would be bad */
- case 0:
- return -EINVAL;
-
- /* set default/max polling rate */
- case SENSOR_POLLRATE_MAX:
- case SENSOR_POLLRATE_DEFAULT: {
- /* do we need to start internal polling? */
- bool want_start = (_measure_ticks == 0);
-
- /* set interval for next measurement to minimum legal value */
- _measure_ticks = USEC2TICK(CONVERSION_INTERVAL);
-
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
-
- return OK;
- }
-
- /* adjust to a legal polling interval in Hz */
- default: {
- /* do we need to start internal polling? */
- bool want_start = (_measure_ticks == 0);
-
- /* convert hz to tick interval via microseconds */
- unsigned ticks = USEC2TICK(1000000 / arg);
-
- /* check against maximum rate */
- if (ticks < USEC2TICK(CONVERSION_INTERVAL))
- return -EINVAL;
-
- /* update interval for next measurement */
- _measure_ticks = ticks;
-
- /* if we need to start the poll state machine, do it */
- if (want_start)
- start();
-
- return OK;
- }
- }
- }
-
- case SENSORIOCGPOLLRATE:
- if (_measure_ticks == 0)
- return SENSOR_POLLRATE_MANUAL;
-
- return (1000 / _measure_ticks);
-
- case SENSORIOCSQUEUEDEPTH: {
- /* add one to account for the sentinel in the ring */
- arg++;
-
- /* lower bound is mandatory, upper bound is a sanity check */
- if ((arg < 2) || (arg > 100))
- return -EINVAL;
-
- /* allocate new buffer */
- struct differential_pressure_s *buf = new struct differential_pressure_s[arg];
-
- if (nullptr == buf)
- return -ENOMEM;
-
- /* reset the measurement state machine with the new buffer, free the old */
- stop();
- delete[] _reports;
- _num_reports = arg;
- _reports = buf;
- start();
-
- return OK;
- }
-
- case SENSORIOCGQUEUEDEPTH:
- return _num_reports - 1;
-
- case SENSORIOCRESET:
- /* XXX implement this */
- return -EINVAL;
-
- default:
- /* give it to the superclass */
- return I2C::ioctl(filp, cmd, arg);
- }
-}
-
-ssize_t
-ETSAirspeed::read(struct file *filp, char *buffer, size_t buflen)
+ETSAirspeed::ETSAirspeed(int bus, int address) : Airspeed(bus, address,
+ CONVERSION_INTERVAL)
{
- unsigned count = buflen / sizeof(struct differential_pressure_s);
- int ret = 0;
-
- /* buffer must be large enough */
- if (count < 1)
- return -ENOSPC;
-
- /* if automatic measurement is enabled */
- if (_measure_ticks > 0) {
-
- /*
- * While there is space in the caller's buffer, and reports, copy them.
- * Note that we may be pre-empted by the workq thread while we are doing this;
- * we are careful to avoid racing with them.
- */
- while (count--) {
- if (_oldest_report != _next_report) {
- memcpy(buffer, _reports + _oldest_report, sizeof(*_reports));
- ret += sizeof(_reports[0]);
- INCREMENT(_oldest_report, _num_reports);
- }
- }
-
- /* if there was no data, warn the caller */
- return ret ? ret : -EAGAIN;
- }
- /* manual measurement - run one conversion */
- /* XXX really it'd be nice to lock against other readers here */
- do {
- _oldest_report = _next_report = 0;
-
- /* trigger a measurement */
- if (OK != measure()) {
- ret = -EIO;
- break;
- }
-
- /* wait for it to complete */
- usleep(CONVERSION_INTERVAL);
-
- /* run the collection phase */
- if (OK != collect()) {
- ret = -EIO;
- break;
- }
-
- /* state machine will have generated a report, copy it out */
- memcpy(buffer, _reports, sizeof(*_reports));
- ret = sizeof(*_reports);
-
- } while (0);
-
- return ret;
}
int
@@ -463,9 +157,15 @@ 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;
+ }
- // XXX move the parameter read out of the driver.
- param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset);
if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
@@ -506,47 +206,6 @@ ETSAirspeed::collect()
}
void
-ETSAirspeed::start()
-{
- /* reset the report ring and state machine */
- _collect_phase = false;
- _oldest_report = _next_report = 0;
-
- /* schedule a cycle to start things */
- work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1);
-
- /* notify about state change */
- struct subsystem_info_s info = {
- true,
- true,
- true,
- SUBSYSTEM_TYPE_DIFFPRESSURE
- };
- static orb_advert_t pub = -1;
-
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
-
- } else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
- }
-}
-
-void
-ETSAirspeed::stop()
-{
- work_cancel(HPWORK, &_work);
-}
-
-void
-ETSAirspeed::cycle_trampoline(void *arg)
-{
- ETSAirspeed *dev = (ETSAirspeed *)arg;
-
- dev->cycle();
-}
-
-void
ETSAirspeed::cycle()
{
/* collection phase? */
@@ -571,7 +230,7 @@ ETSAirspeed::cycle()
/* schedule a fresh cycle call when we are ready to measure again */
work_queue(HPWORK,
&_work,
- (worker_t)&ETSAirspeed::cycle_trampoline,
+ (worker_t)&Airspeed::cycle_trampoline,
this,
_measure_ticks - USEC2TICK(CONVERSION_INTERVAL));
@@ -589,22 +248,11 @@ ETSAirspeed::cycle()
/* schedule a fresh cycle call when the measurement is done */
work_queue(HPWORK,
&_work,
- (worker_t)&ETSAirspeed::cycle_trampoline,
+ (worker_t)&Airspeed::cycle_trampoline,
this,
USEC2TICK(CONVERSION_INTERVAL));
}
-void
-ETSAirspeed::print_info()
-{
- perf_print_counter(_sample_perf);
- perf_print_counter(_comms_errors);
- perf_print_counter(_buffer_overflows);
- printf("poll interval: %u ticks\n", _measure_ticks);
- printf("report queue: %u (%u/%u @ %p)\n",
- _num_reports, _oldest_report, _next_report, _reports);
-}
-
/**
* Local functions in support of the shell command.
*/
@@ -642,7 +290,7 @@ start(int i2c_bus)
if (g_dev == nullptr)
goto fail;
- if (OK != g_dev->init())
+ if (OK != g_dev->Airspeed::init())
goto fail;
/* set the poll rate to default, starts automatic data collection */
@@ -779,11 +427,11 @@ info()
static void
ets_airspeed_usage()
{
- fprintf(stderr, "usage: ets_airspeed command [options]\n");
- fprintf(stderr, "options:\n");
- fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT);
- fprintf(stderr, "command:\n");
- fprintf(stderr, "\tstart|stop|reset|test|info\n");
+ warnx("usage: ets_airspeed command [options]");
+ warnx("options:");
+ warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT);
+ warnx("command:");
+ warnx("\tstart|stop|reset|test|info");
}
int
diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk
index cb5d3b1ed..15346c5c5 100644
--- a/src/drivers/ets_airspeed/module.mk
+++ b/src/drivers/ets_airspeed/module.mk
@@ -36,6 +36,6 @@
#
MODULE_COMMAND = ets_airspeed
-MODULE_STACKSIZE = 1024
+MODULE_STACKSIZE = 2048
SRCS = ets_airspeed.cpp
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
new file mode 100644
index 000000000..7a2e22c01
--- /dev/null
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -0,0 +1,506 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file meas_airspeed.cpp
+ * @author Lorenz Meier
+ * @author Simon Wilks
+ *
+ * Driver for the MEAS Spec series connected via I2C.
+ *
+ * Supported sensors:
+ *
+ * - MS4525DO (http://www.meas-spec.com/downloads/MS4525DO.pdf)
+ * - untested: MS5525DSO (http://www.meas-spec.com/downloads/MS5525DSO.pdf)
+ *
+ * Interface application notes:
+ *
+ * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf)
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <string.h>
+#include <fcntl.h>
+#include <poll.h>
+#include <errno.h>
+#include <stdio.h>
+#include <math.h>
+#include <unistd.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/wqueue.h>
+#include <nuttx/clock.h>
+
+#include <arch/board/board.h>
+
+#include <systemlib/airspeed.h>
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
+
+#include <drivers/drv_airspeed.h>
+#include <drivers/drv_hrt.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/subsystem_info.h>
+
+#include <drivers/airspeed/airspeed.h>
+
+/* I2C bus address is 1010001x */
+#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */
+/* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */
+#define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */
+
+/* Register address */
+#define ADDR_READ_MR 0x00 /* write to this address to start conversion */
+#define ADDR_READ_DF2 0x00 /* read from this address to read pressure only */
+#define ADDR_READ_DF3 0x01
+#define ADDR_READ_DF4 0x02 /* read from this address to read pressure and temp */
+
+/* Measurement rate is 100Hz */
+#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */
+
+class MEASAirspeed : public Airspeed
+{
+public:
+ MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO);
+
+protected:
+
+ /**
+ * Perform a poll cycle; collect from the previous measurement
+ * and start a new one.
+ */
+ virtual void cycle();
+ virtual int measure();
+ virtual int collect();
+
+};
+
+/*
+ * Driver 'main' command.
+ */
+extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]);
+
+MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address,
+ CONVERSION_INTERVAL)
+{
+
+}
+
+int
+MEASAirspeed::measure()
+{
+ int ret;
+
+ /*
+ * Send the command to begin a measurement.
+ */
+ uint8_t cmd = 0;
+ ret = transfer(&cmd, 1, nullptr, 0);
+
+ if (OK != ret) {
+ perf_count(_comms_errors);
+ log("i2c::transfer returned %d", ret);
+ return ret;
+ }
+
+ ret = OK;
+
+ return ret;
+}
+
+int
+MEASAirspeed::collect()
+{
+ int ret = -EIO;
+
+ /* read from the sensor */
+ uint8_t val[4] = {0, 0, 0, 0};
+
+
+ perf_begin(_sample_perf);
+
+ ret = transfer(nullptr, 0, &val[0], 2);
+
+ if (ret < 0) {
+ log("error reading from sensor: %d", ret);
+ return ret;
+ }
+
+ uint8_t status = val[0] & 0xC0;
+
+ if (status == 2) {
+ log("err: stale data");
+ } else if (status == 3) {
+ log("err: fault");
+ }
+
+ uint16_t diff_pres_pa = (val[1]) | ((val[0] & ~(0xC0)) << 8);
+ uint16_t temp = (val[3] & 0xE0) << 8 | val[2];
+
+ diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
+ diff_pres_pa -= _diff_pres_offset;
+
+ // XXX we may want to smooth out the readings to remove noise.
+
+ _reports[_next_report].timestamp = hrt_absolute_time();
+ _reports[_next_report].temperature = temp;
+ _reports[_next_report].differential_pressure_pa = diff_pres_pa;
+
+ // Track maximum differential pressure measured (so we can work out top speed).
+ if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) {
+ _reports[_next_report].max_differential_pressure_pa = diff_pres_pa;
+ }
+
+ /* announce the airspeed if needed, just publish else */
+ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]);
+
+ /* post a report to the ring - note, not locked */
+ INCREMENT(_next_report, _num_reports);
+
+ /* if we are running up against the oldest report, toss it */
+ if (_next_report == _oldest_report) {
+ perf_count(_buffer_overflows);
+ INCREMENT(_oldest_report, _num_reports);
+ }
+
+ /* notify anyone waiting for data */
+ poll_notify(POLLIN);
+
+ ret = OK;
+
+ perf_end(_sample_perf);
+
+ return ret;
+}
+
+void
+MEASAirspeed::cycle()
+{
+ /* collection phase? */
+ if (_collect_phase) {
+
+ /* perform collection */
+ if (OK != collect()) {
+ log("collection error");
+ /* restart the measurement state machine */
+ start();
+ return;
+ }
+
+ /* next phase is measurement */
+ _collect_phase = false;
+
+ /*
+ * Is there a collect->measure gap?
+ */
+ if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) {
+
+ /* schedule a fresh cycle call when we are ready to measure again */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&Airspeed::cycle_trampoline,
+ this,
+ _measure_ticks - USEC2TICK(CONVERSION_INTERVAL));
+
+ return;
+ }
+ }
+
+ /* measurement phase */
+ if (OK != measure())
+ log("measure error");
+
+ /* next phase is collection */
+ _collect_phase = true;
+
+ /* schedule a fresh cycle call when the measurement is done */
+ work_queue(HPWORK,
+ &_work,
+ (worker_t)&Airspeed::cycle_trampoline,
+ this,
+ USEC2TICK(CONVERSION_INTERVAL));
+}
+
+/**
+ * Local functions in support of the shell command.
+ */
+namespace meas_airspeed
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+const int ERROR = -1;
+
+MEASAirspeed *g_dev = nullptr;
+
+void start(int i2c_bus);
+void stop();
+void test();
+void reset();
+void info();
+
+/**
+ * Start the driver.
+ */
+void
+start(int i2c_bus)
+{
+ int fd;
+
+ if (g_dev != nullptr)
+ errx(1, "already started");
+
+ /* create the driver, try the MS4525DO first */
+ g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO);
+
+ /* check if the MS4525DO was instantiated */
+ if (g_dev == nullptr)
+ goto fail;
+
+ /* try the MS5525DSO next if init fails */
+ if (OK != g_dev->Airspeed::init()) {
+ delete g_dev;
+ g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO);
+
+ /* check if the MS5525DSO was instantiated */
+ if (g_dev == nullptr)
+ goto fail;
+
+ /* both versions failed if the init for the MS5525DSO fails, give up */
+ if (OK != g_dev->Airspeed::init())
+ goto fail;
+ }
+
+ /* set the poll rate to default, starts automatic data collection */
+ fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ goto fail;
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ goto fail;
+
+ exit(0);
+
+fail:
+
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+ }
+
+ errx(1, "driver start failed");
+}
+
+/**
+ * Stop the driver
+ */
+void
+stop()
+{
+ if (g_dev != nullptr) {
+ delete g_dev;
+ g_dev = nullptr;
+
+ } else {
+ errx(1, "driver not running");
+ }
+
+ exit(0);
+}
+
+/**
+ * Perform some basic functional tests on the driver;
+ * make sure we can collect data from the sensor in polled
+ * and automatic modes.
+ */
+void
+test()
+{
+ struct differential_pressure_s report;
+ ssize_t sz;
+ int ret;
+
+ int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "%s open failed (try 'meas_airspeed start' if the driver is not running", AIRSPEED_DEVICE_PATH);
+
+ /* do a simple demand read */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ err(1, "immediate read failed");
+
+ warnx("single read");
+ warnx("diff pressure: %d pa", report.differential_pressure_pa);
+
+ /* start the sensor polling at 2Hz */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2))
+ errx(1, "failed to set 2Hz poll rate");
+
+ /* read the sensor 5x and report each value */
+ for (unsigned i = 0; i < 5; i++) {
+ struct pollfd fds;
+
+ /* wait for data to be ready */
+ fds.fd = fd;
+ fds.events = POLLIN;
+ ret = poll(&fds, 1, 2000);
+
+ if (ret != 1)
+ errx(1, "timed out waiting for sensor data");
+
+ /* now go get it */
+ sz = read(fd, &report, sizeof(report));
+
+ if (sz != sizeof(report))
+ err(1, "periodic read failed");
+
+ warnx("periodic read %u", i);
+ warnx("diff pressure: %d pa", report.differential_pressure_pa);
+ warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature);
+ }
+
+ errx(0, "PASS");
+}
+
+/**
+ * Reset the driver.
+ */
+void
+reset()
+{
+ int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "failed ");
+
+ if (ioctl(fd, SENSORIOCRESET, 0) < 0)
+ err(1, "driver reset failed");
+
+ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0)
+ err(1, "driver poll restart failed");
+
+ exit(0);
+}
+
+/**
+ * Print a little info about the driver.
+ */
+void
+info()
+{
+ if (g_dev == nullptr)
+ errx(1, "driver not running");
+
+ printf("state @ %p\n", g_dev);
+ g_dev->print_info();
+
+ exit(0);
+}
+
+} // namespace
+
+
+static void
+meas_airspeed_usage()
+{
+ warnx("usage: meas_airspeed command [options]");
+ warnx("options:");
+ warnx("\t-b --bus i2cbus (%d)", PX4_I2C_BUS_DEFAULT);
+ warnx("command:");
+ warnx("\tstart|stop|reset|test|info");
+}
+
+int
+meas_airspeed_main(int argc, char *argv[])
+{
+ int i2c_bus = PX4_I2C_BUS_DEFAULT;
+
+ int i;
+
+ for (i = 1; i < argc; i++) {
+ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) {
+ if (argc > i + 1) {
+ i2c_bus = atoi(argv[i + 1]);
+ }
+ }
+ }
+
+ /*
+ * Start/load the driver.
+ */
+ if (!strcmp(argv[1], "start"))
+ meas_airspeed::start(i2c_bus);
+
+ /*
+ * Stop the driver
+ */
+ if (!strcmp(argv[1], "stop"))
+ meas_airspeed::stop();
+
+ /*
+ * Test the driver/device.
+ */
+ if (!strcmp(argv[1], "test"))
+ meas_airspeed::test();
+
+ /*
+ * Reset the driver.
+ */
+ if (!strcmp(argv[1], "reset"))
+ meas_airspeed::reset();
+
+ /*
+ * Print driver information.
+ */
+ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status"))
+ meas_airspeed::info();
+
+ meas_airspeed_usage();
+ exit(0);
+}
diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk
new file mode 100644
index 000000000..fed4078b6
--- /dev/null
+++ b/src/drivers/meas_airspeed/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Makefile to build the MEAS Spec airspeed sensor driver.
+#
+
+MODULE_COMMAND = meas_airspeed
+MODULE_STACKSIZE = 2048
+
+SRCS = meas_airspeed.cpp
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index 8d9054a38..1fd6cb17e 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -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();
diff --git a/src/modules/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c
index dc653a079..6a304896a 100644
--- a/src/modules/commander/accelerometer_calibration.c
+++ b/src/modules/commander/accelerometer_calibration.c
@@ -268,8 +268,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) {
float accel_disp[3] = { 0.0f, 0.0f, 0.0f };
/* EMA time constant in seconds*/
float ema_len = 0.2f;
- /* set "still" threshold to 0.1 m/s^2 */
- float still_thr2 = pow(0.1f, 2);
+ /* set "still" threshold to 0.25 m/s^2 */
+ float still_thr2 = pow(0.25f, 2);
/* set accel error threshold to 5m/s^2 */
float accel_err_thr = 5.0f;
/* still time required in us */
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index 8e5e36712..e9d1f3954 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -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;
}
}
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 252c1b7a9..133cda8d6 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -68,7 +68,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f);
PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
-PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667);
+PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 1667);
PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f);
PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index b2a6c6a79..7ff9e19b4 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -60,6 +60,7 @@
#include <drivers/drv_baro.h>
#include <drivers/drv_rc_input.h>
#include <drivers/drv_adc.h>
+#include <drivers/drv_airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -197,7 +198,7 @@ private:
float mag_scale[3];
float accel_offset[3];
float accel_scale[3];
- int diff_pres_offset_pa;
+ float diff_pres_offset_pa;
int rc_type;
@@ -230,6 +231,7 @@ private:
float battery_voltage_scaling;
int rc_rl1_DSM_VCC_control;
+
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -280,6 +282,7 @@ private:
param_t battery_voltage_scaling;
param_t rc_rl1_DSM_VCC_control;
+
} _parameter_handles; /**< handles for interesting parameters */
@@ -391,7 +394,7 @@ namespace sensors
#endif
static const int ERROR = -1;
-Sensors *g_sensors;
+Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
@@ -554,25 +557,11 @@ Sensors::parameters_update()
/* rc values */
for (unsigned int i = 0; i < RC_CHANNELS_MAX; i++) {
- if (param_get(_parameter_handles.min[i], &(_parameters.min[i])) != OK) {
- warnx("Failed getting min for chan %d", i);
- }
-
- if (param_get(_parameter_handles.trim[i], &(_parameters.trim[i])) != OK) {
- warnx("Failed getting trim for chan %d", i);
- }
-
- if (param_get(_parameter_handles.max[i], &(_parameters.max[i])) != OK) {
- warnx("Failed getting max for chan %d", i);
- }
-
- if (param_get(_parameter_handles.rev[i], &(_parameters.rev[i])) != OK) {
- warnx("Failed getting rev for chan %d", i);
- }
-
- if (param_get(_parameter_handles.dz[i], &(_parameters.dz[i])) != OK) {
- warnx("Failed getting dead zone for chan %d", i);
- }
+ param_get(_parameter_handles.min[i], &(_parameters.min[i]));
+ param_get(_parameter_handles.trim[i], &(_parameters.trim[i]));
+ param_get(_parameter_handles.max[i], &(_parameters.max[i]));
+ param_get(_parameter_handles.rev[i], &(_parameters.rev[i]));
+ param_get(_parameter_handles.dz[i], &(_parameters.dz[i]));
_parameters.scaling_factor[i] = (1.0f / ((_parameters.max[i] - _parameters.min[i]) / 2.0f) * _parameters.rev[i]);
@@ -662,21 +651,10 @@ Sensors::parameters_update()
warnx("Failed getting mode aux 5 index");
}
- if (param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll)) != OK) {
- warnx("Failed getting rc scaling for roll");
- }
-
- if (param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch)) != OK) {
- warnx("Failed getting rc scaling for pitch");
- }
-
- if (param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw)) != OK) {
- warnx("Failed getting rc scaling for yaw");
- }
-
- if (param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps)) != OK) {
- warnx("Failed getting rc scaling for flaps");
- }
+ param_get(_parameter_handles.rc_scale_roll, &(_parameters.rc_scale_roll));
+ param_get(_parameter_handles.rc_scale_pitch, &(_parameters.rc_scale_pitch));
+ param_get(_parameter_handles.rc_scale_yaw, &(_parameters.rc_scale_yaw));
+ param_get(_parameter_handles.rc_scale_flaps, &(_parameters.rc_scale_flaps));
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -1041,6 +1019,20 @@ Sensors::parameter_update_poll(bool forced)
close(fd);
+ fd = open(AIRSPEED_DEVICE_PATH, 0);
+
+ /* this sensor is optional, abort without error */
+
+ if (fd > 0) {
+ struct airspeed_scale airscale = {
+ _parameters.diff_pres_offset_pa,
+ 1.0f,
+ };
+
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ }
+
#if 0
printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]);
printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]);
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
new file mode 100644
index 000000000..2dad2261b
--- /dev/null
+++ b/src/systemcmds/config/config.c
@@ -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);
+}
diff --git a/src/systemcmds/config/module.mk b/src/systemcmds/config/module.mk
new file mode 100644
index 000000000..0a75810b0
--- /dev/null
+++ b/src/systemcmds/config/module.mk
@@ -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
+
diff --git a/src/systemcmds/ramtron/module.mk b/src/systemcmds/ramtron/module.mk
new file mode 100644
index 000000000..e4eb1d143
--- /dev/null
+++ b/src/systemcmds/ramtron/module.mk
@@ -0,0 +1,6 @@
+#
+# RAMTRON file system driver
+#
+
+MODULE_COMMAND = ramtron
+SRCS = ramtron.c
diff --git a/src/systemcmds/ramtron/ramtron.c b/src/systemcmds/ramtron/ramtron.c
new file mode 100644
index 000000000..03c713987
--- /dev/null
+++ b/src/systemcmds/ramtron/ramtron.c
@@ -0,0 +1,279 @@
+/****************************************************************************
+ *
+ * Copyright (C) 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 ramtron.c
+ *
+ * ramtron service and utility app.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdbool.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <sys/mount.h>
+#include <sys/ioctl.h>
+#include <sys/stat.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/mtd.h>
+#include <nuttx/fs/nxffs.h>
+#include <nuttx/fs/ioctl.h>
+
+#include <arch/board/board.h>
+
+#include "systemlib/systemlib.h"
+#include "systemlib/param/param.h"
+#include "systemlib/err.h"
+
+__EXPORT int ramtron_main(int argc, char *argv[]);
+
+#ifndef CONFIG_MTD_RAMTRON
+
+/* create a fake command with decent message to not confuse users */
+int ramtron_main(int argc, char *argv[])
+{
+ errx(1, "RAMTRON not enabled, skipping.");
+}
+#else
+
+static void ramtron_attach(void);
+static void ramtron_start(void);
+static void ramtron_erase(void);
+static void ramtron_ioctl(unsigned operation);
+static void ramtron_save(const char *name);
+static void ramtron_load(const char *name);
+static void ramtron_test(void);
+
+static bool attached = false;
+static bool started = false;
+static struct mtd_dev_s *ramtron_mtd;
+
+int ramtron_main(int argc, char *argv[])
+{
+ if (argc >= 2) {
+ if (!strcmp(argv[1], "start"))
+ ramtron_start();
+
+ if (!strcmp(argv[1], "save_param"))
+ ramtron_save(argv[2]);
+
+ if (!strcmp(argv[1], "load_param"))
+ ramtron_load(argv[2]);
+
+ if (!strcmp(argv[1], "erase"))
+ ramtron_erase();
+
+ if (!strcmp(argv[1], "test"))
+ ramtron_test();
+
+ if (0) { /* these actually require a file on the filesystem... */
+
+ if (!strcmp(argv[1], "reformat"))
+ ramtron_ioctl(FIOC_REFORMAT);
+
+ if (!strcmp(argv[1], "repack"))
+ ramtron_ioctl(FIOC_OPTIMIZE);
+ }
+ }
+
+ errx(1, "expected a command, try 'start'\n\t'save_param /ramtron/parameters'\n\t'load_param /ramtron/parameters'\n\t'erase'\n");
+}
+
+struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev);
+
+
+static void
+ramtron_attach(void)
+{
+ /* find the right spi */
+ struct spi_dev_s *spi = up_spiinitialize(2);
+ /* this resets the spi bus, set correct bus speed again */
+ // xxx set in ramtron driver, leave this out
+// SPI_SETFREQUENCY(spi, 4000000);
+ SPI_SETFREQUENCY(spi, 375000000);
+ SPI_SETBITS(spi, 8);
+ SPI_SETMODE(spi, SPIDEV_MODE3);
+ SPI_SELECT(spi, SPIDEV_FLASH, false);
+
+ if (spi == NULL)
+ errx(1, "failed to locate spi bus");
+
+ /* start the MTD driver, attempt 5 times */
+ for (int i = 0; i < 5; i++) {
+ ramtron_mtd = ramtron_initialize(spi);
+ if (ramtron_mtd) {
+ /* abort on first valid result */
+ if (i > 0) {
+ warnx("warning: ramtron needed %d attempts to attach", i+1);
+ }
+ break;
+ }
+ }
+
+ /* if last attempt is still unsuccessful, abort */
+ if (ramtron_mtd == NULL)
+ errx(1, "failed to initialize ramtron driver");
+
+ attached = true;
+}
+
+static void
+ramtron_start(void)
+{
+ int ret;
+
+ if (started)
+ errx(1, "ramtron already mounted");
+
+ if (!attached)
+ ramtron_attach();
+
+ /* start NXFFS */
+ ret = nxffs_initialize(ramtron_mtd);
+
+ if (ret < 0)
+ errx(1, "failed to initialize NXFFS - erase ramtron to reformat");
+
+ /* mount the ramtron */
+ ret = mount(NULL, "/ramtron", "nxffs", 0, NULL);
+
+ if (ret < 0)
+ errx(1, "failed to mount /ramtron - erase ramtron to reformat");
+
+ started = true;
+ warnx("mounted ramtron at /ramtron");
+ exit(0);
+}
+
+//extern int at24c_nuke(void);
+
+static void
+ramtron_erase(void)
+{
+ if (!attached)
+ ramtron_attach();
+
+// if (at24c_nuke())
+ errx(1, "erase failed");
+
+ errx(0, "erase done, reboot now");
+}
+
+static void
+ramtron_ioctl(unsigned operation)
+{
+ int fd;
+
+ fd = open("/ramtron/.", 0);
+
+ if (fd < 0)
+ err(1, "open /ramtron");
+
+ if (ioctl(fd, operation, 0) < 0)
+ err(1, "ioctl");
+
+ exit(0);
+}
+
+static void
+ramtron_save(const char *name)
+{
+ if (!started)
+ errx(1, "must be started first");
+
+ if (!name)
+ err(1, "missing argument for device name, try '/ramtron/parameters'");
+
+ warnx("WARNING: 'ramtron save_param' deprecated - use 'param save' instead");
+
+ /* delete the file in case it exists */
+ unlink(name);
+
+ /* create the file */
+ int fd = open(name, O_WRONLY | O_CREAT | O_EXCL);
+
+ if (fd < 0)
+ err(1, "opening '%s' failed", name);
+
+ int result = param_export(fd, false);
+ close(fd);
+
+ if (result < 0) {
+ unlink(name);
+ errx(1, "error exporting to '%s'", name);
+ }
+
+ exit(0);
+}
+
+static void
+ramtron_load(const char *name)
+{
+ if (!started)
+ errx(1, "must be started first");
+
+ if (!name)
+ err(1, "missing argument for device name, try '/ramtron/parameters'");
+
+ warnx("WARNING: 'ramtron load_param' deprecated - use 'param load' instead");
+
+ int fd = open(name, O_RDONLY);
+
+ if (fd < 0)
+ err(1, "open '%s'", name);
+
+ int result = param_load(fd);
+ close(fd);
+
+ if (result < 0)
+ errx(1, "error importing from '%s'", name);
+
+ exit(0);
+}
+
+//extern void at24c_test(void);
+
+static void
+ramtron_test(void)
+{
+// at24c_test();
+ exit(0);
+}
+
+#endif