aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--Documentation/commander_app.odgbin11628 -> 0 bytes
-rw-r--r--Documentation/commander_app.pngbin25356 -> 0 bytes
-rw-r--r--Documentation/dsm_bind.odtbin27043 -> 27123 bytes
-rw-r--r--Documentation/dsm_bind.pdfbin34300 -> 323311 bytes
-rw-r--r--Documentation/flight_mode_state_machine.odgbin22619 -> 18452 bytes
-rw-r--r--Documentation/mixing_architecture.graffle4398
-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/rc_mode_switch.odgbin14631 -> 14872 bytes
-rw-r--r--Documentation/rc_mode_switch.pdfbin15841 -> 16097 bytes
-rw-r--r--Documentation/state_machine.odgbin18576 -> 0 bytes
-rw-r--r--Documentation/state_machine.pngbin208880 -> 0 bytes
-rw-r--r--Firmware.sublime-project3
-rw-r--r--Makefile124
-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/40_io_segway122
-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--ROMFS/px4fmu_common/logging/conv.zipbin0 -> 10087 bytes
-rw-r--r--Tools/README.txt13
-rw-r--r--Tools/logconv.m (renamed from ROMFS/px4fmu_common/logging/logconv.m)231
-rw-r--r--Tools/logconv.py59
-rw-r--r--Tools/sdlog2_dump.py102
-rw-r--r--makefiles/board_px4fmu-v1.mk1
-rw-r--r--makefiles/board_px4io-v1.mk1
-rw-r--r--makefiles/config_px4fmu-v1_default.mk6
-rw-r--r--makefiles/firmware.mk3
-rw-r--r--makefiles/module.mk3
-rw-r--r--makefiles/setup.mk1
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk7
-rw-r--r--makefiles/upload.mk2
-rw-r--r--nuttx-configs/px4fmu-v1/include/board.h391
-rw-r--r--nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h42
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/Make.defs179
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig964
-rwxr-xr-xnuttx-configs/px4fmu-v1/nsh/setenv.sh75
-rw-r--r--nuttx-configs/px4fmu-v1/scripts/ld.script149
-rw-r--r--nuttx-configs/px4fmu-v1/src/Makefile84
-rw-r--r--nuttx-configs/px4fmu-v1/src/empty.c4
-rwxr-xr-xnuttx-configs/px4io-v1/include/README.txt1
-rwxr-xr-xnuttx-configs/px4io-v1/include/board.h168
-rw-r--r--nuttx-configs/px4io-v1/nsh/Make.defs166
-rw-r--r--nuttx-configs/px4io-v1/nsh/appconfig32
-rwxr-xr-xnuttx-configs/px4io-v1/nsh/defconfig537
-rwxr-xr-xnuttx-configs/px4io-v1/nsh/setenv.sh47
-rwxr-xr-xnuttx-configs/px4io-v1/scripts/ld.script129
-rw-r--r--nuttx-configs/px4io-v1/src/Makefile84
-rw-r--r--nuttx-configs/px4io-v1/src/empty.c4
-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/device/cdev.cpp16
-rw-r--r--src/drivers/device/device.cpp19
-rw-r--r--src/drivers/device/device.h70
-rw-r--r--src/drivers/device/i2c.h14
-rw-r--r--src/drivers/device/ringbuffer.h203
-rw-r--r--src/drivers/device/spi.h2
-rw-r--r--src/drivers/drv_airspeed.h9
-rw-r--r--src/drivers/drv_pwm_output.h5
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp402
-rw-r--r--src/drivers/ets_airspeed/module.mk2
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp9
-rw-r--r--src/drivers/md25/BlockSysIdent.cpp8
-rw-r--r--src/drivers/md25/BlockSysIdent.hpp10
-rw-r--r--src/drivers/md25/md25.cpp87
-rw-r--r--src/drivers/md25/md25.hpp18
-rw-r--r--src/drivers/md25/md25_main.cpp49
-rw-r--r--src/drivers/meas_airspeed/meas_airspeed.cpp520
-rw-r--r--src/drivers/meas_airspeed/module.mk41
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp402
-rw-r--r--src/drivers/px4io/px4io.cpp63
-rw-r--r--src/drivers/stm32/drv_hrt.c20
-rw-r--r--src/drivers/stm32/drv_pwm_servo.c6
-rw-r--r--src/drivers/stm32/tone_alarm/tone_alarm.cpp4
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp4
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp10
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp4
-rw-r--r--src/modules/commander/commander.cpp3
-rw-r--r--src/modules/controllib/block/Block.cpp4
-rw-r--r--src/modules/controllib/blocks.hpp1
-rw-r--r--src/modules/controllib/module.mk8
-rw-r--r--src/modules/controllib/uorb/UOrbPublication.cpp (renamed from src/modules/controllib/block/UOrbPublication.cpp)0
-rw-r--r--src/modules/controllib/uorb/UOrbPublication.hpp (renamed from src/modules/controllib/block/UOrbPublication.hpp)4
-rw-r--r--src/modules/controllib/uorb/UOrbSubscription.cpp (renamed from src/modules/controllib/block/UOrbSubscription.cpp)0
-rw-r--r--src/modules/controllib/uorb/UOrbSubscription.hpp (renamed from src/modules/controllib/block/UOrbSubscription.hpp)4
-rw-r--r--src/modules/controllib/uorb/blocks.cpp101
-rw-r--r--src/modules/controllib/uorb/blocks.hpp113
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp (renamed from src/modules/controllib/fixedwing.cpp)57
-rw-r--r--src/modules/fixedwing_backside/fixedwing.hpp (renamed from src/modules/controllib/fixedwing.hpp)68
-rw-r--r--src/modules/fixedwing_backside/fixedwing_backside_main.cpp3
-rw-r--r--src/modules/fixedwing_backside/module.mk1
-rw-r--r--src/modules/mathlib/math/filter/LowPassFilter2p.cpp77
-rw-r--r--src/modules/mathlib/math/filter/LowPassFilter2p.hpp78
-rw-r--r--src/modules/mathlib/math/filter/module.mk44
-rw-r--r--src/modules/px4iofirmware/controls.c2
-rw-r--r--src/modules/px4iofirmware/dsm.c4
-rw-r--r--src/modules/sdlog2/sdlog2.c11
-rw-r--r--src/modules/segway/BlockSegwayController.cpp57
-rw-r--r--src/modules/segway/BlockSegwayController.hpp27
-rw-r--r--src/modules/segway/module.mk42
-rw-r--r--src/modules/segway/params.c8
-rw-r--r--src/modules/segway/segway_main.cpp157
-rw-r--r--src/modules/sensors/sensor_params.c3
-rw-r--r--src/modules/sensors/sensors.cpp156
-rw-r--r--src/modules/systemlib/hx_stream.c185
-rw-r--r--src/modules/systemlib/hx_stream.h42
-rw-r--r--src/modules/systemlib/perf_counter.c41
-rw-r--r--src/modules/systemlib/perf_counter.h14
-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
-rw-r--r--src/systemcmds/tests/test_hrt.c2
118 files changed, 11506 insertions, 1189 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/dsm_bind.odt b/Documentation/dsm_bind.odt
index 66ea1f1be..587a38883 100644
--- a/Documentation/dsm_bind.odt
+++ b/Documentation/dsm_bind.odt
Binary files differ
diff --git a/Documentation/dsm_bind.pdf b/Documentation/dsm_bind.pdf
index e62d1ed83..76155569e 100644
--- a/Documentation/dsm_bind.pdf
+++ b/Documentation/dsm_bind.pdf
Binary files differ
diff --git a/Documentation/flight_mode_state_machine.odg b/Documentation/flight_mode_state_machine.odg
index 2d119bd8c..f9fa7a032 100644
--- a/Documentation/flight_mode_state_machine.odg
+++ b/Documentation/flight_mode_state_machine.odg
Binary files differ
diff --git a/Documentation/mixing_architecture.graffle b/Documentation/mixing_architecture.graffle
new file mode 100644
index 000000000..da8027bf7
--- /dev/null
+++ b/Documentation/mixing_architecture.graffle
@@ -0,0 +1,4398 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0">
+<dict>
+ <key>ActiveLayerIndex</key>
+ <integer>0</integer>
+ <key>ApplicationVersion</key>
+ <array>
+ <string>com.omnigroup.OmniGraffle</string>
+ <string>139.17.0.185490</string>
+ </array>
+ <key>AutoAdjust</key>
+ <true/>
+ <key>BackgroundGraphic</key>
+ <dict>
+ <key>Bounds</key>
+ <string>{{0, 0}, {1118, 783}}</string>
+ <key>Class</key>
+ <string>SolidGraphic</string>
+ <key>ID</key>
+ <integer>2</integer>
+ <key>Style</key>
+ <dict>
+ <key>shadow</key>
+ <dict>
+ <key>Draws</key>
+ <string>NO</string>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>Draws</key>
+ <string>NO</string>
+ </dict>
+ </dict>
+ </dict>
+ <key>BaseZoom</key>
+ <integer>0</integer>
+ <key>CanvasOrigin</key>
+ <string>{0, 0}</string>
+ <key>ColumnAlign</key>
+ <integer>1</integer>
+ <key>ColumnSpacing</key>
+ <real>36</real>
+ <key>CreationDate</key>
+ <string>2013-06-04 09:23:13 +0000</string>
+ <key>Creator</key>
+ <string>Lorenz Meier</string>
+ <key>DisplayScale</key>
+ <string>1 0/72 in = 1.0000 in</string>
+ <key>GraphDocumentVersion</key>
+ <integer>8</integer>
+ <key>GraphicsList</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>508</integer>
+ </dict>
+ <key>ID</key>
+ <integer>635</integer>
+ <key>Points</key>
+ <array>
+ <string>{106.17826841821868, 273.42634001636537}</string>
+ <string>{213.16101457128596, 357.82365814026997}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>613</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>507</integer>
+ </dict>
+ <key>ID</key>
+ <integer>634</integer>
+ <key>Points</key>
+ <array>
+ <string>{131.96398352136816, 273.42634001634866}</string>
+ <string>{238.946729674436, 357.82365813972365}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>612</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{482, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>617</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{456.21429061889648, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>618</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{430.42857551574707, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>619</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{404.64286041259766, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>620</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{378.85714530944824, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>621</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{353.07143020629883, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>622</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{327.28571510314941, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>623</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{301.5, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>624</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{482, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>625</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{456.21429061889648, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>626</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{430.42857551574707, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>627</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{404.64286041259766, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>628</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{378.85714530944824, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>629</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{353.07143020629883, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>630</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{327.28571510314941, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>631</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{301.5, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>632</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{291.5, 235.24999816050627}, {208, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>633</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 Actuator Control Group 1}</string>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>616</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>587</integer>
+ </dict>
+ <key>ID</key>
+ <integer>592</integer>
+ <key>Points</key>
+ <array>
+ <string>{605.82627753848249, 74.5}</string>
+ <string>{716.81658859616107, 159.07205874840687}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>581</integer>
+ </dict>
+ <key>ID</key>
+ <integer>591</integer>
+ <key>Points</key>
+ <array>
+ <string>{576.14671565757703, 75.907219770052052}</string>
+ <string>{565.99614475502062, 157.66483897835485}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>ID</key>
+ <integer>590</integer>
+ <key>Points</key>
+ <array>
+ <string>{565.49194626385997, 201.66102838314328}</string>
+ <string>{565.21582473837202, 338.8005880984627}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>573</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>ID</key>
+ <integer>589</integer>
+ <key>Points</key>
+ <array>
+ <string>{720.20623661457341, 201.6610283823652}</string>
+ <string>{719.9301058948314, 338.80058788427203}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>579</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{743, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>588</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{717.21429061889648, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>587</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{691.42857551574707, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>586</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{665.64286041259766, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>585</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{639.85714530944824, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>584</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{614.07143020629883, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>583</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{588.28571510314941, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>582</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{562.5, 158.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>581</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{743, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>580</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{717.21429061889648, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>579</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{691.42857551574707, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>578</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{665.64286041259766, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>577</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{639.85714530944824, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>576</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{614.07143020629883, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>575</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{588.28571510314941, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>574</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{562.5, 194.16102937420345}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>573</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{552.5, 162.16102937420345}, {208, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>572</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 RC Scaling &amp; Mapping}</string>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>509</integer>
+ </dict>
+ <key>ID</key>
+ <integer>569</integer>
+ <key>Points</key>
+ <array>
+ <string>{80.392553315069293, 273.42634001641937}</string>
+ <string>{187.37529946813521, 357.82365814202342}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>614</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>506</integer>
+ </dict>
+ <key>ID</key>
+ <integer>596</integer>
+ <key>Points</key>
+ <array>
+ <string>{378.46463924118007, 273.4271429546975}</string>
+ <string>{271.51750416091619, 357.82285520170717}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>629</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{254.5, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>599</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{228.71429061889648, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>600</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{202.92857551574707, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>601</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{177.14286041259766, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>602</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{151.35714530944824, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>603</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{125.57143020629883, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>604</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{99.785715103149414, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>605</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{74, 231.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>606</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{254.5, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>607</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{228.71429061889648, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>608</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{202.92857551574707, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>609</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{177.14286041259766, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>610</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{151.35714530944824, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>611</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{125.57143020629883, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>612</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{99.785715103149414, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>613</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{74, 267.24999816050627}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>614</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{64, 235.24999816050627}, {208, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>615</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 Actuator Control Group 0}</string>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>598</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>474</integer>
+ </dict>
+ <key>ID</key>
+ <integer>411</integer>
+ <key>Points</key>
+ <array>
+ <string>{322.59687445702775, 444.84226761008853}</string>
+ <string>{379.20669915150745, 526.90773238985753}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>510</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>477</integer>
+ </dict>
+ <key>ID</key>
+ <integer>412</integer>
+ <key>Points</key>
+ <array>
+ <string>{294.62113860994009, 444.9967148570675}</string>
+ <string>{304.03957452010235, 526.7532851429479}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>511</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>490</integer>
+ </dict>
+ <key>ID</key>
+ <integer>413</integer>
+ <key>Points</key>
+ <array>
+ <string>{290.76782961936522, 443.67073351699491}</string>
+ <string>{183.53574398902853, 528.07926647675936}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>511</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>491</integer>
+ </dict>
+ <key>ID</key>
+ <integer>414</integer>
+ <key>Points</key>
+ <array>
+ <string>{264.9821145162158, 443.67073351699491}</string>
+ <string>{157.75002888587912, 528.07926647675936}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>512</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>492</integer>
+ </dict>
+ <key>ID</key>
+ <integer>415</integer>
+ <key>Points</key>
+ <array>
+ <string>{239.19639941306636, 443.67073351699491}</string>
+ <string>{131.9643137827297, 528.07926647675936}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>513</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>493</integer>
+ </dict>
+ <key>ID</key>
+ <integer>416</integer>
+ <key>Points</key>
+ <array>
+ <string>{213.41068430991695, 443.67073351699491}</string>
+ <string>{106.1785986795803, 528.07926647675936}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>514</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>440</integer>
+ </dict>
+ <key>ID</key>
+ <integer>417</integer>
+ <key>Points</key>
+ <array>
+ <string>{304.49194626386003, 570.74999900893988}</string>
+ <string>{304.21582473837134, 707.88955872425925}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>485</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>429</integer>
+ </dict>
+ <key>ID</key>
+ <integer>418</integer>
+ <key>Points</key>
+ <array>
+ <string>{381.84909342488743, 570.74999900816329}</string>
+ <string>{381.57303538097813, 707.88955851048831}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>482</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{379.35432048604451, 719.00347978513389}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>421</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{396.74606011338682, 726.18083608931011}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>422</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{391.6252245834844, 724.37750550833903}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>423</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{386.29980802056684, 722.50213058402392}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>424</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{375.67643661590967, 718.76105153253593}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>425</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{370.35101205342835, 716.88567379113056}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>426</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{365.23018452308935, 715.08234602724974}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>427</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{345.93778549185652, 717.4003115566619}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>428</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>420</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{371.98798359082144, 708.38955751823028}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>429</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>419</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{301.99718791759841, 719.00348000010274}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>432</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{319.38892754494066, 726.18083630427896}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>433</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{314.26809201503823, 724.37750572330788}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>434</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{308.94267545212068, 722.50213079899277}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>435</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{298.3193040474635, 718.76105174750478}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>436</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{292.99387948498219, 716.88567400609941}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>437</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{287.87305195464319, 715.08234624221859}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>438</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{268.58065292341041, 717.40031177163075}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>439</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>431</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{294.63085102237534, 708.38955773319913}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>440</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>430</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{151.85433513439526, 676.40348606783687}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>443</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{169.24607476173759, 683.58084237201308}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>444</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{164.12523923183511, 681.777511791042}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>445</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{158.79982266891756, 679.90213686672689}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>446</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{148.17645126426038, 676.16105781523891}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>447</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{142.85102670177906, 674.28568007383353}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>448</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{137.73019917144009, 672.48235230995272}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>449</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{118.43780014020726, 674.80031783936488}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>450</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>442</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{144.48799823917219, 665.78956380093325}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>451</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>441</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{126.06861430919994, 649.30352977035523}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>454</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{143.46035393654228, 656.48088607453144}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>455</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{138.3395184066398, 654.67755549356036}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>456</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{133.01410184372224, 652.80218056924525}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>457</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{122.39073043906507, 649.06110151775727}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>458</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{117.06530587658375, 647.18572377635189}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>459</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{111.94447834624478, 645.38239601247108}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>460</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{92.652079315011946, 647.70036154188324}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>461</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>453</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{118.70227741397687, 638.68960750345161}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>462</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>452</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>494</integer>
+ </dict>
+ <key>ID</key>
+ <integer>463</integer>
+ <key>Points</key>
+ <array>
+ <string>{187.62496920676753, 443.67073351699486}</string>
+ <string>{80.392883576430918, 528.07926647675936}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>515</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>451</integer>
+ </dict>
+ <key>ID</key>
+ <integer>464</integer>
+ <key>Points</key>
+ <array>
+ <string>{154.34620841108131, 570.74999811167606}</string>
+ <string>{154.08771587848975, 665.2895656892573}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>499</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>462</integer>
+ </dict>
+ <key>ID</key>
+ <integer>465</integer>
+ <key>Points</key>
+ <array>
+ <string>{128.55726775049197, 570.74999689176411}</string>
+ <string>{128.31848992771231, 638.1896106116875}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>500</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>538</integer>
+ </dict>
+ <key>ID</key>
+ <integer>466</integer>
+ <key>Points</key>
+ <array>
+ <string>{102.76581371331335, 570.74999379087535}</string>
+ <string>{102.56212456317996, 611.68961371257615}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>501</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>549</integer>
+ </dict>
+ <key>ID</key>
+ <integer>467</integer>
+ <key>Points</key>
+ <array>
+ <string>{76.966539516560758, 570.74998251647355}</string>
+ <string>{76.84574963416425, 585.18962498697681}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>502</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>550</integer>
+ </dict>
+ <key>ID</key>
+ <integer>468</integer>
+ <key>Points</key>
+ <array>
+ <string>{180.14284120598458, 570.75}</string>
+ <string>{180.14284120598458, 685.34997558593727}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>498</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>LineGraphic</string>
+ <key>Head</key>
+ <dict>
+ <key>ID</key>
+ <integer>527</integer>
+ </dict>
+ <key>ID</key>
+ <integer>469</integer>
+ <key>Points</key>
+ <array>
+ <string>{205.92052173345891, 570.74999897014993}</string>
+ <string>{205.64439858308342, 707.8895785636937}</string>
+ </array>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>HeadArrow</key>
+ <string>FilledArrow</string>
+ <key>Legacy</key>
+ <true/>
+ <key>TailArrow</key>
+ <string>0</string>
+ </dict>
+ </dict>
+ <key>Tail</key>
+ <dict>
+ <key>ID</key>
+ <integer>497</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{482, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>470</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{456.21429061889648, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>471</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{430.42857551574707, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>472</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{404.64286041259766, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>473</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{378.85714530944824, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>474</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{353.07143020629883, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>475</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{327.28571510314941, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>476</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{301.5, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>477</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{482, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>478</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{456.21429061889648, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>479</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{430.42857551574707, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>480</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{404.64286041259766, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>481</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{378.85714530944824, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>482</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{353.07143020629883, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>483</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{327.28571510314941, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>484</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{301.5, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>485</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{291.5, 531.25}, {208, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>486</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 Actuator Output Group 1 (e.g. FMU)}</string>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{254.5, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>487</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{228.71429061889648, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>488</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{202.92857551574707, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>489</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{177.14286041259766, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>490</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{151.35714530944824, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>491</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{125.57143020629883, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>492</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{99.785715103149414, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>493</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{74, 527.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>494</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{254.5, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>495</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{228.71429061889648, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>496</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{202.92857551574707, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>497</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{177.14286041259766, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>498</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{151.35714530944824, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>499</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{125.57143020629883, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>500</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{99.785715103149414, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>501</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{74, 563.25}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>502</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{64, 531.25}, {208, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>503</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 Actuator Output Group 0 (e.g. IO)}</string>
+ </dict>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{265.12499809265137, 357}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>506</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{239.33928298950195, 357}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>507</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{213.55356788635254, 357}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>508</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{187.76785278320312, 357}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>509</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{316.9464282989502, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>510</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{291.16071319580078, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>511</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{265.37499809265137, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>512</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{239.58928298950195, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>513</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{213.80356788635254, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>514</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{188.01785278320312, 437.5}, {6, 7}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>515</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>1</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>505</integer>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{177.14285278320312, 359.75}, {208, 82}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>516</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>9</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 Vehicle Mixer}</string>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>504</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{203.42576152599673, 719.00349980074725}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>519</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{220.81750115333907, 726.18085610492346}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>520</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{215.69666562343659, 724.37752552395239}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>521</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{210.37124906051903, 722.50215059963728}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>522</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{199.74787765586186, 718.76107154814929}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>523</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{194.42245309338054, 716.88569380674392}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>524</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{189.30162556304157, 715.0823660428631}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>525</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{170.00922653180874, 717.40033157227526}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>526</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>518</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{196.05942463077366, 708.38957753384364}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>527</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>517</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{100.28290111339905, 622.80352977035523}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>530</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{117.67464074074138, 629.98088607453144}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>531</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{112.5538052108389, 628.17755549356036}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>532</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{107.22838864792135, 626.30218056924525}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>533</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{96.605017243264172, 622.56110151775727}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>534</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{91.279592680782855, 620.68572377635189}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>535</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{86.158765150443884, 618.88239601247108}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>536</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{66.866366119211051, 621.20036154188324}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>537</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>529</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{92.916564218175978, 612.18960750345161}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>538</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>528</integer>
+ </dict>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Class</key>
+ <string>Group</string>
+ <key>Graphics</key>
+ <array>
+ <dict>
+ <key>Bounds</key>
+ <string>{{74.49718852803673, 596.30352977035523}, {5.0056232242123722, 4.9183513058348947}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>541</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{91.888928155379034, 603.48088607453144}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>542</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{86.768092625476555, 601.67755549356036}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>543</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{81.442676062559002, 599.80218056924525}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>544</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{70.819304657901824, 596.06110151775727}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>545</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{65.493880095420508, 594.18572377635189}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>546</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{60.373052565081537, 592.38239601247108}, {1.9456694882012362, 1.7352345929064885}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>547</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Circle</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{41.080653533848704, 594.70036154188324}, {71.838699340820256, 8.1246847180976189}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>548</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>540</integer>
+ <key>Rotation</key>
+ <real>19.399997711181641</real>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{67.130851632813631, 585.68960750345161}, {19.087577050122338, 39.91038694100309}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>549</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.153172</string>
+ <key>g</key>
+ <string>0.153172</string>
+ <key>r</key>
+ <string>0.153172</string>
+ </dict>
+ <key>FillType</key>
+ <integer>2</integer>
+ <key>GradientAngle</key>
+ <real>145</real>
+ <key>GradientColor</key>
+ <dict>
+ <key>b</key>
+ <string>0.416928</string>
+ <key>g</key>
+ <string>0.416928</string>
+ <key>r</key>
+ <string>0.416928</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>CornerRadius</key>
+ <real>2</real>
+ </dict>
+ </dict>
+ </dict>
+ </array>
+ <key>ID</key>
+ <integer>539</integer>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{64, 104}, {54, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>1</integer>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{125.57142639160156, 24}, {36, 36}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>6</integer>
+ <key>Shape</key>
+ <string>Diamond</string>
+ <key>Style</key>
+ <dict/>
+ <key>Text</key>
+ <dict>
+ <key>VerticalPad</key>
+ <integer>0</integer>
+ </dict>
+ </dict>
+ <dict>
+ <key>Bounds</key>
+ <string>{{158.14285217276469, 695.84997558593727}, {44, 24}}</string>
+ <key>Class</key>
+ <string>ShapedGraphic</string>
+ <key>ID</key>
+ <integer>550</integer>
+ <key>Rotation</key>
+ <real>90</real>
+ <key>Shape</key>
+ <string>Rectangle</string>
+ <key>Style</key>
+ <dict>
+ <key>fill</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.243722</string>
+ <key>g</key>
+ <string>0.864482</string>
+ <key>r</key>
+ <string>1</string>
+ </dict>
+ </dict>
+ <key>stroke</key>
+ <dict>
+ <key>Color</key>
+ <dict>
+ <key>b</key>
+ <string>0.051159</string>
+ <key>g</key>
+ <string>0.160546</string>
+ <key>r</key>
+ <string>0.18663</string>
+ </dict>
+ <key>CornerRadius</key>
+ <real>5</real>
+ </dict>
+ </dict>
+ <key>Text</key>
+ <dict>
+ <key>Text</key>
+ <string>{\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370
+\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;}
+{\colortbl;\red255\green255\blue255;}
+\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc
+
+\f0\fs24 \cf0 ESC}</string>
+ </dict>
+ </dict>
+ </array>
+ <key>GridInfo</key>
+ <dict/>
+ <key>GuidesLocked</key>
+ <string>NO</string>
+ <key>GuidesVisible</key>
+ <string>YES</string>
+ <key>HPages</key>
+ <integer>2</integer>
+ <key>ImageCounter</key>
+ <integer>1</integer>
+ <key>KeepToScale</key>
+ <false/>
+ <key>Layers</key>
+ <array>
+ <dict>
+ <key>Lock</key>
+ <string>NO</string>
+ <key>Name</key>
+ <string>Layer 1</string>
+ <key>Print</key>
+ <string>YES</string>
+ <key>View</key>
+ <string>YES</string>
+ </dict>
+ </array>
+ <key>LayoutInfo</key>
+ <dict>
+ <key>Animate</key>
+ <string>NO</string>
+ <key>circoMinDist</key>
+ <real>18</real>
+ <key>circoSeparation</key>
+ <real>0.0</real>
+ <key>layoutEngine</key>
+ <string>dot</string>
+ <key>neatoSeparation</key>
+ <real>0.0</real>
+ <key>twopiSeparation</key>
+ <real>0.0</real>
+ </dict>
+ <key>LinksVisible</key>
+ <string>NO</string>
+ <key>MagnetsVisible</key>
+ <string>NO</string>
+ <key>MasterSheets</key>
+ <array/>
+ <key>ModificationDate</key>
+ <string>2013-06-04 16:51:32 +0000</string>
+ <key>Modifier</key>
+ <string>Lorenz Meier</string>
+ <key>NotesVisible</key>
+ <string>NO</string>
+ <key>Orientation</key>
+ <integer>2</integer>
+ <key>OriginVisible</key>
+ <string>NO</string>
+ <key>PageBreaks</key>
+ <string>YES</string>
+ <key>PrintInfo</key>
+ <dict>
+ <key>NSBottomMargin</key>
+ <array>
+ <string>float</string>
+ <string>41</string>
+ </array>
+ <key>NSHorizonalPagination</key>
+ <array>
+ <string>coded</string>
+ <string>BAtzdHJlYW10eXBlZIHoA4QBQISEhAhOU051bWJlcgCEhAdOU1ZhbHVlAISECE5TT2JqZWN0AIWEASqEhAFxlwCG</string>
+ </array>
+ <key>NSLeftMargin</key>
+ <array>
+ <string>float</string>
+ <string>18</string>
+ </array>
+ <key>NSPaperSize</key>
+ <array>
+ <string>size</string>
+ <string>{595, 842}</string>
+ </array>
+ <key>NSPrintReverseOrientation</key>
+ <array>
+ <string>int</string>
+ <string>0</string>
+ </array>
+ <key>NSRightMargin</key>
+ <array>
+ <string>float</string>
+ <string>18</string>
+ </array>
+ <key>NSTopMargin</key>
+ <array>
+ <string>float</string>
+ <string>18</string>
+ </array>
+ </dict>
+ <key>PrintOnePage</key>
+ <false/>
+ <key>ReadOnly</key>
+ <string>NO</string>
+ <key>RowAlign</key>
+ <integer>1</integer>
+ <key>RowSpacing</key>
+ <real>36</real>
+ <key>SheetTitle</key>
+ <string>Canvas 1</string>
+ <key>SmartAlignmentGuidesActive</key>
+ <string>YES</string>
+ <key>SmartDistanceGuidesActive</key>
+ <string>YES</string>
+ <key>UniqueID</key>
+ <integer>1</integer>
+ <key>UseEntirePage</key>
+ <false/>
+ <key>VPages</key>
+ <integer>1</integer>
+ <key>WindowInfo</key>
+ <dict>
+ <key>CurrentSheet</key>
+ <integer>0</integer>
+ <key>ExpandedCanvases</key>
+ <array>
+ <dict>
+ <key>name</key>
+ <string>Canvas 1</string>
+ </dict>
+ </array>
+ <key>Frame</key>
+ <string>{{176, 63}, {1581, 1355}}</string>
+ <key>ListView</key>
+ <true/>
+ <key>OutlineWidth</key>
+ <integer>142</integer>
+ <key>RightSidebar</key>
+ <false/>
+ <key>ShowRuler</key>
+ <true/>
+ <key>Sidebar</key>
+ <true/>
+ <key>SidebarWidth</key>
+ <integer>120</integer>
+ <key>VisibleRegion</key>
+ <string>{{-164, -216}, {1446, 1216}}</string>
+ <key>Zoom</key>
+ <real>1</real>
+ <key>ZoomValues</key>
+ <array>
+ <array>
+ <string>Canvas 1</string>
+ <real>1</real>
+ <real>2</real>
+ </array>
+ </array>
+ </dict>
+</dict>
+</plist>
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/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg
index e35a83372..a8a6f93f3 100644
--- a/Documentation/rc_mode_switch.odg
+++ b/Documentation/rc_mode_switch.odg
Binary files differ
diff --git a/Documentation/rc_mode_switch.pdf b/Documentation/rc_mode_switch.pdf
index 823b1d868..3141eed7f 100644
--- a/Documentation/rc_mode_switch.pdf
+++ b/Documentation/rc_mode_switch.pdf
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/Firmware.sublime-project b/Firmware.sublime-project
index 72bacee9f..7292307d5 100644
--- a/Firmware.sublime-project
+++ b/Firmware.sublime-project
@@ -32,7 +32,8 @@
"settings":
{
"tab_size": 8,
- "translate_tabs_to_spaces": false
+ "translate_tabs_to_spaces": false,
+ "highlight_line": true
},
"build_systems":
[
diff --git a/Makefile b/Makefile
index 7f98ffaf2..778395cee 100644
--- a/Makefile
+++ b/Makefile
@@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES)
# is taken care of.
#
$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
- @echo %% Copying $@
+ @$(ECHO) %% Copying $@
$(Q) $(COPY) $< $@
$(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@)
@@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
- @echo %%%%
- @echo %%%% Building $(config) in $(work_dir)
- @echo %%%%
+ @$(ECHO) %%%%
+ @$(ECHO) %%%% Building $(config) in $(work_dir)
+ @$(ECHO) %%%%
$(Q) mkdir -p $(work_dir)
$(Q) make -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
@@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
# XXX Should support fetching/unpacking from a separate directory to permit
# downloads of the prebuilt archives as well...
#
-# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4"
-#
NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
.PHONY: archives
archives: $(NUTTX_ARCHIVES)
@@ -146,15 +144,54 @@ endif
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
$(ARCHIVE_DIR)%.export: configuration = nsh
-$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
- @echo %% Configuring NuttX for $(board)
+$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
+ @$(ECHO) %% Configuring NuttX for $(board)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
- @echo %% Exporting NuttX for $(board)
- $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
+ @$(ECHO) %% Exporting NuttX for $(board)
+ $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) mkdir -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
+ $(Q) (cd $(NUTTX_SRC)/configs && $(RMDIR) $(board))
+
+#
+# The user can run the NuttX 'menuconfig' tool for a single board configuration with
+# make BOARDS=<boardname> menuconfig
+#
+ifeq ($(MAKECMDGOALS),menuconfig)
+ifneq ($(words $(BOARDS)),1)
+$(error BOARDS must specify exactly one board for the menuconfig goal)
+endif
+BOARD = $(BOARDS)
+menuconfig: $(NUTTX_SRC)
+ @$(ECHO) %% Configuring NuttX for $(BOARD)
+ $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
+ $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(BOARD) .)
+ $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(BOARD)/nsh)
+ @$(ECHO) %% Running menuconfig for $(BOARD)
+ $(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) menuconfig
+ @$(ECHO) %% Saving configuration file
+ $(Q)$(COPY) $(NUTTX_SRC).config $(PX4_BASE)nuttx-configs/$(BOARD)/nsh/defconfig
+else
+menuconfig:
+ @$(ECHO) ""
+ @$(ECHO) "The menuconfig goal must be invoked without any other goal being specified"
+ @$(ECHO) ""
+endif
+
+$(NUTTX_SRC):
+ @$(ECHO) ""
+ @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again."
+ @$(ECHO) ""
+
+#
+# Testing targets
+#
+testbuild:
+ $(Q) (cd $(PX4_BASE) && make distclean && make archives && make -j8)
#
# Cleanup targets. 'clean' should remove all built products and force
@@ -176,40 +213,43 @@ distclean: clean
#
.PHONY: help
help:
- @echo ""
- @echo " PX4 firmware builder"
- @echo " ===================="
- @echo ""
- @echo " Available targets:"
- @echo " ------------------"
- @echo ""
- @echo " archives"
- @echo " Build the NuttX RTOS archives that are used by the firmware build."
- @echo ""
- @echo " all"
- @echo " Build all firmware configs: $(CONFIGS)"
- @echo " A limited set of configs can be built with CONFIGS=<list-of-configs>"
- @echo ""
+ @$(ECHO) ""
+ @$(ECHO) " PX4 firmware builder"
+ @$(ECHO) " ===================="
+ @$(ECHO) ""
+ @$(ECHO) " Available targets:"
+ @$(ECHO) " ------------------"
+ @$(ECHO) ""
+ @$(ECHO) " archives"
+ @$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build."
+ @$(ECHO) ""
+ @$(ECHO) " all"
+ @$(ECHO) " Build all firmware configs: $(CONFIGS)"
+ @$(ECHO) " A limited set of configs can be built with CONFIGS=<list-of-configs>"
+ @$(ECHO) ""
@for config in $(CONFIGS); do \
echo " $$config"; \
echo " Build just the $$config firmware configuration."; \
echo ""; \
done
- @echo " clean"
- @echo " Remove all firmware build pieces."
- @echo ""
- @echo " distclean"
- @echo " Remove all compilation products, including NuttX RTOS archives."
- @echo ""
- @echo " upload"
- @echo " When exactly one config is being built, add this target to upload the"
- @echo " firmware to the board when the build is complete. Not supported for"
- @echo " all configurations."
- @echo ""
- @echo " Common options:"
- @echo " ---------------"
- @echo ""
- @echo " V=1"
- @echo " If V is set, more verbose output is printed during the build. This can"
- @echo " help when diagnosing issues with the build or toolchain."
- @echo ""
+ @$(ECHO) " clean"
+ @$(ECHO) " Remove all firmware build pieces."
+ @$(ECHO) ""
+ @$(ECHO) " distclean"
+ @$(ECHO) " Remove all compilation products, including NuttX RTOS archives."
+ @$(ECHO) ""
+ @$(ECHO) " upload"
+ @$(ECHO) " When exactly one config is being built, add this target to upload the"
+ @$(ECHO) " firmware to the board when the build is complete. Not supported for"
+ @$(ECHO) " all configurations."
+ @$(ECHO) ""
+ @$(ECHO) " testbuild"
+ @$(ECHO) " Perform a complete clean build of the entire tree."
+ @$(ECHO) ""
+ @$(ECHO) " Common options:"
+ @$(ECHO) " ---------------"
+ @$(ECHO) ""
+ @$(ECHO) " V=1"
+ @$(ECHO) " If V is set, more verbose output is printed during the build. This can"
+ @$(ECHO) " help when diagnosing issues with the build or toolchain."
+ @$(ECHO) ""
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/40_io_segway b/ROMFS/px4fmu_common/init.d/40_io_segway
new file mode 100644
index 000000000..5742d685a
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/40_io_segway
@@ -0,0 +1,122 @@
+#!nsh
+#
+# Flight startup script for PX4FMU+PX4IO
+#
+
+# disable USB and autostart
+set USB no
+set MODE custom
+
+#
+# Start the ORB (first app to start)
+#
+uorb start
+
+#
+# Load microSD params
+#
+echo "[init] loading microSD params"
+param select /fs/microsd/params
+if [ -f /fs/microsd/params ]
+then
+ param load /fs/microsd/params
+fi
+
+#
+# Load default params for this platform
+#
+if param compare SYS_AUTOCONFIG 1
+then
+ # Set all params here, then disable autoconfig
+ param set SYS_AUTOCONFIG 0
+ param save /fs/microsd/params
+fi
+
+#
+# Force some key parameters to sane values
+# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
+# see https://pixhawk.ethz.ch/mavlink/
+#
+param set MAV_TYPE 10
+
+#
+# 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
+usleep 5000
+
+#
+# Start the commander (depends on orb, mavlink)
+#
+commander start
+
+#
+# Start PX4IO interface (depends on orb, commander)
+#
+px4io start
+
+#
+# Allow PX4IO to recover from midair restarts.
+# this is very unlikely, but quite safe and robust.
+px4io recovery
+
+#
+# Disable px4io topic limiting
+#
+px4io limit 200
+
+#
+# Start the sensors (depends on orb, px4io)
+#
+sh /etc/init.d/rc.sensors
+
+#
+# Start GPS interface (depends on orb)
+#
+gps start
+
+#
+# Start the attitude estimator (depends on orb)
+#
+attitude_estimator_ekf start
+
+#
+# Load mixer and start controllers (depends on px4io)
+#
+md25 start 3 0x58
+segway start
+
+#
+# Start logging
+#
+sdlog2 start -r 50 -a -b 14
+
+#
+# Start system state
+#
+if blinkm start
+then
+ blinkm systemstate
+fi
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/ROMFS/px4fmu_common/logging/conv.zip b/ROMFS/px4fmu_common/logging/conv.zip
new file mode 100644
index 000000000..7cb837e56
--- /dev/null
+++ b/ROMFS/px4fmu_common/logging/conv.zip
Binary files differ
diff --git a/Tools/README.txt b/Tools/README.txt
new file mode 100644
index 000000000..abeb9a4c7
--- /dev/null
+++ b/Tools/README.txt
@@ -0,0 +1,13 @@
+====== PX4 LOG CONVERSION ======
+
+On each log session (commonly started and stopped by arming and disarming the vehicle) a new file logxxx.bin is created. In many cases there will be only one logfile named log001.bin (only one flight).
+
+There are two conversion scripts in this ZIP file:
+
+logconv.m: This is a MATLAB script which will automatically convert and display the flight data with a GUI. If running this script, the second script can be ignored.
+
+sdlog2_dump.py: This is a Python script (compatible with v2 and v3) which converts the self-describing binary log format to a CSV file. To export a CSV file from within a shell (Windows CMD or BASH on Linux / Mac OS), run:
+
+python sdlog2_dump.py log001.bin -f "export.csv" -t "TIME" -d "," -n ""
+
+Python can be downloaded from http://python.org, but is available as default on Mac OS and Linux. \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/logging/logconv.m b/Tools/logconv.m
index 3750ddae2..c416b8095 100644
--- a/ROMFS/px4fmu_common/logging/logconv.m
+++ b/Tools/logconv.m
@@ -16,7 +16,7 @@ close all
% ************************************************************************
% Set the path to your sysvector.bin file here
-filePath = 'sysvector.bin';
+filePath = 'log001.bin';
% Set the minimum and maximum times to plot here [in seconds]
mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start]
@@ -26,8 +26,8 @@ maxtime=0; %The maximum time/timestamp to display, as set by the user [0
bDisplayGPS=true;
%conversion factors
-fconv_gpsalt=1E-3; %[mm] to [m]
-fconv_gpslatlong=1E-7; %[gps_raw_position_unit] to [deg]
+fconv_gpsalt=1; %[mm] to [m]
+fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg]
fconv_timestamp=1E-6; % [microseconds] to [seconds]
% ************************************************************************
@@ -36,7 +36,7 @@ fconv_timestamp=1E-6; % [microseconds] to [seconds]
ImportPX4LogData();
%Translate min and max plot times to indices
-time=double(sysvector.timestamp) .*fconv_timestamp;
+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
@@ -76,109 +76,48 @@ DrawCurrentAircraftState();
% 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()
- % Work around a Matlab bug (not related to PX4)
- % where timestamps from 1.1.1970 do not allow to
- % read the file's size
- if ismac
- system('touch -t 201212121212.12 sysvector.bin');
- end
% ************************************************************************
% RETRIEVE SYSTEM VECTOR
% *************************************************************************
% //All measurements in NED frame
- %
- % uint64_t timestamp; //[us]
- % float gyro[3]; //[rad/s]
- % float accel[3]; //[m/s^2]
- % float mag[3]; //[gauss]
- % float baro; //pressure [millibar]
- % float baro_alt; //altitude above MSL [meter]
- % float baro_temp; //[degree celcius]
- % float control[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
- % float actuators[8]; //motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512)
- % float vbat; //battery voltage in [volt]
- % float bat_current - current drawn from battery at this time instant
- % float bat_discharged - discharged energy in mAh
- % float adc[4]; //remaining auxiliary ADC ports [volt]
- % float local_position[3]; //tangent plane mapping into x,y,z [m]
- % int32_t gps_raw_position[3]; //latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter]
- % float attitude[3]; //pitch, roll, yaw [rad]
- % float rotMatrix[9]; //unitvectors
- % float actuator_control[4]; //unitvector
- % float optical_flow[4]; //roll, pitch, yaw [-1..1], thrust [0..1]
- % float diff_pressure; - pressure difference in millibar
- % float ind_airspeed;
- % float true_airspeed;
-
- % Definition of the logged values
- logFormat{1} = struct('name', 'timestamp', 'bytes', 8, 'array', 1, 'precision', 'uint64', 'machineformat', 'ieee-le.l64');
- logFormat{2} = struct('name', 'gyro', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{3} = struct('name', 'accel', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{4} = struct('name', 'mag', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{5} = struct('name', 'baro', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{6} = struct('name', 'baro_alt', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{7} = struct('name', 'baro_temp', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{8} = struct('name', 'control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{9} = struct('name', 'actuators', 'bytes', 4, 'array', 8, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{10} = struct('name', 'vbat', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{11} = struct('name', 'bat_current', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{12} = struct('name', 'bat_discharged', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{13} = struct('name', 'adc', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{14} = struct('name', 'local_position', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{15} = struct('name', 'gps_raw_position', 'bytes', 4, 'array', 3, 'precision', 'uint32', 'machineformat', 'ieee-le');
- logFormat{16} = struct('name', 'attitude', 'bytes', 4, 'array', 3, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{17} = struct('name', 'rot_matrix', 'bytes', 4, 'array', 9, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{18} = struct('name', 'vicon_position', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{19} = struct('name', 'actuator_control', 'bytes', 4, 'array', 4, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{20} = struct('name', 'optical_flow', 'bytes', 4, 'array', 6, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{21} = struct('name', 'diff_pressure', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{22} = struct('name', 'ind_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
- logFormat{23} = struct('name', 'true_airspeed', 'bytes', 4, 'array', 1, 'precision', 'float', 'machineformat', 'ieee-le');
-
- % First get length of one line
- columns = length(logFormat);
- lineLength = 0;
-
- for i=1:columns
- lineLength = lineLength + logFormat{i}.bytes * logFormat{i}.array;
+
+ % 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')
- if exist(filePath, 'file')
-
- fileInfo = dir(filePath);
- fileSize = fileInfo.bytes;
-
- elements = int64(fileSize./(lineLength));
-
- fid = fopen(filePath, 'r');
- offset = 0;
- for i=1:columns
- % using fread with a skip speeds up the import drastically, do not
- % import the values one after the other
- sysvector.(genvarname(logFormat{i}.name)) = transpose(fread(...
- fid, ...
- [logFormat{i}.array, elements], [num2str(logFormat{i}.array),'*',logFormat{i}.precision,'=>',logFormat{i}.precision], ...
- lineLength - logFormat{i}.bytes*logFormat{i}.array, ...
- logFormat{i}.machineformat) ...
- );
- offset = offset + logFormat{i}.bytes*logFormat{i}.array;
- fseek(fid, offset,'bof');
- end
+ %data = csvread(data_file);
+ sysvector = tdfread(data_file, ',');
% shot the flight time
- time_us = sysvector.timestamp(end) - sysvector.timestamp(1);
- time_s = time_us*1e-6;
- time_m = time_s/60;
-
- % close the logfile
- fclose(fid);
+ time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1);
+ time_s = uint64(time_us*1e-6);
+ time_m = uint64(time_s/60);
+ time_s = time_s - time_m * 60;
+
+ disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]);
- disp(['end log2matlab conversion' char(10)]);
+ disp(['logfile conversion finished.' char(10)]);
else
- disp(['file: ' filePath ' does not exist' char(10)]);
+ disp(['file: ' data_file ' does not exist' char(10)]);
end
end
@@ -296,11 +235,11 @@ function DrawRawData()
% ************************************************************************
figure(h.figures(2));
% Only plot GPS data if available
- if (sum(double(sysvector.gps_raw_position(imintime:imaxtime,1)))>0) && (bDisplayGPS)
+ if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS)
%Draw data
- plot3(h.axes(1),double(sysvector.gps_raw_position(imintime:imaxtime,1))*fconv_gpslatlong, ...
- double(sysvector.gps_raw_position(imintime:imaxtime,2))*fconv_gpslatlong, ...
- double(sysvector.gps_raw_position(imintime:imaxtime,3))*fconv_gpsalt,'r.');
+ 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]');
@@ -315,19 +254,19 @@ function DrawRawData()
% PLOT WINDOW 2: IMU, baro altitude
% ************************************************************************
figure(h.figures(3));
- plot(h.axes(2),time(imintime:imaxtime),sysvector.mag(imintime:imaxtime,:));
+ 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.accel(imintime:imaxtime,:));
+ 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.gyro(imintime:imaxtime,:));
+ 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.baro_alt(imintime:imaxtime),'color','blue');
+ 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_raw_position(imintime:imaxtime,3)).*fconv_gpsalt,'color','red');
+ 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
@@ -340,22 +279,22 @@ function DrawRawData()
% ************************************************************************
figure(h.figures(4));
%Attitude Estimate
- plot(h.axes(6),time(imintime:imaxtime), sysvector.attitude(imintime:imaxtime,:).*180./3.14159);
+ 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.actuator_control(imintime:imaxtime,:));
+ 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),'0','1','2','3');
+ 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.actuators(imintime:imaxtime,1:8));
+ 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.ind_airspeed(imintime:imaxtime));
+ plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime));
hold on
- plot(h.axes(9),time(imintime:imaxtime), sysvector.true_airspeed(imintime:imaxtime));
+ 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]');
@@ -385,33 +324,43 @@ function DrawCurrentAircraftState()
%**********************************************************************
% Current aircraft state label update
%**********************************************************************
- acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong),'°, ',...
- 'lon=',num2str(double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong),'°, ',...
- 'alt=',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]'];
- acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.mag(i,1)),...
- ', y=',num2str(sysvector.mag(i,2)),...
- ', z=',num2str(sysvector.mag(i,3)),']'];
- acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.accel(i,1)),...
- ', y=',num2str(sysvector.accel(i,2)),...
- ', z=',num2str(sysvector.accel(i,3)),']'];
- acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.gyro(i,1)),...
- ', y=',num2str(sysvector.gyro(i,2)),...
- ', z=',num2str(sysvector.gyro(i,3)),']'];
- acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.baro_alt(i)),'m, GPS: ',num2str(double(sysvector.gps_raw_position(i,3))*fconv_gpsalt),'m]'];
- acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.attitude(i,1).*180./3.14159),...
- ', Pitch=',num2str(sysvector.attitude(i,2).*180./3.14159),...
- ', Yaw=',num2str(sysvector.attitude(i,3).*180./3.14159),']'];
+ 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.actuator_control(i,j)),','];
- end
+ %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.actuators(i,j)),','];
- end
+ %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.ind_airspeed(i)),', TAS: ',num2str(sysvector.true_airspeed(i)),']'];
+ 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);
@@ -422,13 +371,13 @@ function DrawCurrentAircraftState()
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_raw_position(imintime:i,1))*fconv_gpslatlong, ...
- double(sysvector.gps_raw_position(imintime:i,2))*fconv_gpslatlong, ...
- double(sysvector.gps_raw_position(imintime:i,3))*fconv_gpsalt,'b','LineWidth',2);
+ 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_raw_position(i,1))*fconv_gpslatlong double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong double(sysvector.gps_raw_position(i,3))*fconv_gpsalt];
+ 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
@@ -443,8 +392,8 @@ function DrawCurrentAircraftState()
if(isvalidhandle(h.markertext))
delete(h.markertext); %delete old text
end
- h.markertext=text(double(sysvector.gps_raw_position(i,1))*fconv_gpslatlong,double(sysvector.gps_raw_position(i,2))*fconv_gpslatlong,...
- double(sysvector.gps_raw_position(i,3))*fconv_gpsalt,textdesc);
+ 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);
%**********************************************************************
@@ -549,11 +498,11 @@ end
% FINDMINMAXINDICES (nested function)
% ************************************************************************
function [idxmin,idxmax] = FindMinMaxTimeIndices()
- for i=1:size(sysvector.timestamp,1)
+ for i=1:size(sysvector.TIME_StartTime,1)
if time(i)>=mintime; idxmin=i; break; end
end
- for i=1:size(sysvector.timestamp,1)
- if maxtime==0; idxmax=size(sysvector.timestamp,1); break; 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);
diff --git a/Tools/logconv.py b/Tools/logconv.py
deleted file mode 100644
index c47d22a45..000000000
--- a/Tools/logconv.py
+++ /dev/null
@@ -1,59 +0,0 @@
-#!/usr/bin/env python
-
-"""Convert binary log generated by sdlog to CSV format
-
-Usage: python logconv.py <log.bin>"""
-
-__author__ = "Anton Babushkin"
-__version__ = "0.1"
-
-import struct, sys
-
-def _unpack_packet(data):
- s = ""
- s += "Q" #.timestamp = buf.raw.timestamp,
- s += "fff" #.gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]},
- s += "fff" #.accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]},
- s += "fff" #.mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]},
- s += "f" #.baro = buf.raw.baro_pres_mbar,
- s += "f" #.baro_alt = buf.raw.baro_alt_meter,
- s += "f" #.baro_temp = buf.raw.baro_temp_celcius,
- s += "ffff" #.control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]},
- s += "ffffffff" #.actuators = {buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3], buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]},
- s += "f" #.vbat = buf.batt.voltage_v,
- s += "f" #.bat_current = buf.batt.current_a,
- s += "f" #.bat_discharged = buf.batt.discharged_mah,
- s += "ffff" #.adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]},
- s += "fff" #.local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z},
- s += "iii" #.gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt},
- s += "fff" #.attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw},
- s += "fffffffff" #.rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]},
- s += "fff" #.vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw},
- s += "ffff" #.control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]},
- s += "ffffff" #.flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality},
- s += "f" #.diff_pressure = buf.diff_pres.differential_pressure_pa,
- s += "f" #.ind_airspeed = buf.airspeed.indicated_airspeed_m_s,
- s += "f" #.true_airspeed = buf.airspeed.true_airspeed_m_s
- s += "iii" # to align to 280
- d = struct.unpack(s, data)
- return d
-
-def _main():
- if len(sys.argv) < 2:
- print "Usage:\npython logconv.py <log.bin>"
- return
- fn = sys.argv[1]
- sysvector_size = 280
- f = open(fn, "r")
- while True:
- data = f.read(sysvector_size)
- if len(data) < sysvector_size:
- break
- a = []
- for i in _unpack_packet(data):
- a.append(str(i))
- print ";".join(a)
- f.close()
-
-if __name__ == "__main__":
- _main()
diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2_dump.py
index 318f72971..7fefc5908 100644
--- a/Tools/sdlog2_dump.py
+++ b/Tools/sdlog2_dump.py
@@ -1,6 +1,8 @@
#!/usr/bin/env python
-"""Dump binary log generated by sdlog2 or APM as CSV
+from __future__ import print_function
+
+"""Dump binary log generated by PX4's sdlog2 or APM as CSV
Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]]
@@ -21,6 +23,11 @@ __version__ = "1.2"
import struct, sys
+if sys.hexversion >= 0x030000F0:
+ runningPython3 = True
+else:
+ runningPython3 = False
+
class SDLog2Parser:
BLOCK_SIZE = 8192
MSG_HEADER_LEN = 3
@@ -55,6 +62,8 @@ class SDLog2Parser:
__time_msg = None
__debug_out = False
__correct_errors = False
+ __file_name = None
+ __file = None
def __init__(self):
return
@@ -63,7 +72,7 @@ class SDLog2Parser:
self.__msg_descrs = {} # message descriptions by message type map
self.__msg_labels = {} # message labels by message name map
self.__msg_names = [] # message names in the same order as FORMAT messages
- self.__buffer = "" # buffer for input binary data
+ self.__buffer = bytearray() # buffer for input binary data
self.__ptr = 0 # read pointer in buffer
self.__csv_columns = [] # CSV file columns in correct order in format "MSG.label"
self.__csv_data = {} # current values for all columns
@@ -87,6 +96,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()
@@ -95,7 +112,7 @@ class SDLog2Parser:
for msg_name, show_fields in self.__msg_filter:
self.__msg_filter_map[msg_name] = show_fields
first_data_msg = True
- f = open(fn, "r")
+ f = open(fn, "rb")
bytes_read = 0
while True:
chunk = f.read(self.BLOCK_SIZE)
@@ -104,15 +121,15 @@ class SDLog2Parser:
self.__buffer = self.__buffer[self.__ptr:] + chunk
self.__ptr = 0
while self.__bytesLeft() >= self.MSG_HEADER_LEN:
- head1 = ord(self.__buffer[self.__ptr])
- head2 = ord(self.__buffer[self.__ptr+1])
+ head1 = self.__buffer[self.__ptr]
+ head2 = self.__buffer[self.__ptr+1]
if (head1 != self.MSG_HEAD1 or head2 != self.MSG_HEAD2):
if self.__correct_errors:
self.__ptr += 1
continue
else:
raise Exception("Invalid header at %i (0x%X): %02X %02X, must be %02X %02X" % (bytes_read + self.__ptr, bytes_read + self.__ptr, head1, head2, self.MSG_HEAD1, self.MSG_HEAD2))
- msg_type = ord(self.__buffer[self.__ptr+2])
+ msg_type = self.__buffer[self.__ptr+2]
if msg_type == self.MSG_TYPE_FORMAT:
# parse FORMAT message
if self.__bytesLeft() < self.MSG_FORMAT_PACKET_LEN:
@@ -154,10 +171,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.__csv_delim.join(self.__csv_columns), file=self.__file)
+ else:
+ print(self.__csv_delim.join(self.__csv_columns))
def __printCSVRow(self):
s = []
@@ -168,16 +188,28 @@ class SDLog2Parser:
else:
v = str(v)
s.append(v)
- print self.__csv_delim.join(s)
+
+ if self.__file != None:
+ print(self.__csv_delim.join(s), file=self.__file)
+ 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])
+ if runningPython3:
+ data = struct.unpack(self.MSG_FORMAT_STRUCT, self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN])
+ else:
+ data = struct.unpack(self.MSG_FORMAT_STRUCT, str(self.__buffer[self.__ptr + 3 : self.__ptr + self.MSG_FORMAT_PACKET_LEN]))
msg_type = data[0]
if msg_type != self.MSG_TYPE_FORMAT:
msg_length = data[1]
- msg_name = data[2].strip("\0")
- msg_format = data[3].strip("\0")
- msg_labels = data[4].strip("\0").split(",")
+ if runningPython3:
+ msg_name = str(data[2], 'ascii').strip("\0")
+ msg_format = str(data[3], 'ascii').strip("\0")
+ msg_labels = str(data[4], 'ascii').strip("\0").split(",")
+ else:
+ msg_name = str(data[2]).strip("\0")
+ msg_format = str(data[3]).strip("\0")
+ msg_labels = str(data[4]).strip("\0").split(",")
# Convert msg_format to struct.unpack format string
msg_struct = ""
msg_mults = []
@@ -194,8 +226,8 @@ class SDLog2Parser:
self.__msg_names.append(msg_name)
if self.__debug_out:
if self.__filterMsg(msg_name) != None:
- print "MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (
- msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults)
+ print("MSG FORMAT: type = %i, length = %i, name = %s, format = %s, labels = %s, struct = %s, mults = %s" % (
+ msg_type, msg_length, msg_name, msg_format, str(msg_labels), msg_struct, msg_mults))
self.__ptr += self.MSG_FORMAT_PACKET_LEN
def __parseMsg(self, msg_descr):
@@ -205,8 +237,11 @@ class SDLog2Parser:
self.__csv_updated = False
show_fields = self.__filterMsg(msg_name)
if (show_fields != None):
- data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))
- for i in xrange(len(data)):
+ if runningPython3:
+ data = list(struct.unpack(msg_struct, self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length]))
+ else:
+ data = list(struct.unpack(msg_struct, str(self.__buffer[self.__ptr+self.MSG_HEADER_LEN:self.__ptr+msg_length])))
+ for i in range(len(data)):
if type(data[i]) is str:
data[i] = data[i].strip("\0")
m = msg_mults[i]
@@ -214,17 +249,17 @@ class SDLog2Parser:
data[i] = data[i] * m
if self.__debug_out:
s = []
- for i in xrange(len(data)):
+ for i in range(len(data)):
label = msg_labels[i]
if show_fields == "*" or label in show_fields:
s.append(label + "=" + str(data[i]))
- print "MSG %s: %s" % (msg_name, ", ".join(s))
+ print("MSG %s: %s" % (msg_name, ", ".join(s)))
else:
# update CSV data buffer
- for i in xrange(len(data)):
+ for i in range(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:
@@ -233,13 +268,14 @@ class SDLog2Parser:
def _main():
if len(sys.argv) < 2:
- print "Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n"
- print "\t-v\tUse plain debug output instead of CSV.\n"
- print "\t-e\tRecover from errors.\n"
- print "\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n"
- print "\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n"
- print "\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed."
- print "\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n"
+ print("Usage: python sdlog2_dump.py <log.bin> [-v] [-e] [-d delimiter] [-n null] [-m MSG[.field1,field2,...]] [-t TIME_MSG_NAME]\n")
+ print("\t-v\tUse plain debug output instead of CSV.\n")
+ print("\t-e\tRecover from errors.\n")
+ print("\t-d\tUse \"delimiter\" in CSV. Default is \",\".\n")
+ print("\t-n\tUse \"null\" as placeholder for empty values in CSV. Default is empty.\n")
+ print("\t-m MSG[.field1,field2,...]\n\t\tDump only messages of specified type, and only specified fields.\n\t\tMultiple -m options allowed.")
+ print("\t-t\tSpecify TIME message name to group data messages by time and significantly reduce duplicate output.\n")
+ print("\t-fPrint to file instead of stdout")
return
fn = sys.argv[1]
debug_out = False
@@ -247,7 +283,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 +294,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 +316,8 @@ def _main():
opt = "m"
elif arg == "-t":
opt = "t"
+ elif arg == "-f":
+ opt = "f"
if csv_delim == "\\t":
csv_delim = "\t"
@@ -285,6 +326,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/board_px4fmu-v1.mk b/makefiles/board_px4fmu-v1.mk
index 837069644..4d692e31a 100644
--- a/makefiles/board_px4fmu-v1.mk
+++ b/makefiles/board_px4fmu-v1.mk
@@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM4F
+CONFIG_BOARD = PX4FMU_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/board_px4io-v1.mk b/makefiles/board_px4io-v1.mk
index b0eb2dae7..1872a4124 100644
--- a/makefiles/board_px4io-v1.mk
+++ b/makefiles/board_px4io-v1.mk
@@ -6,5 +6,6 @@
# Configure the toolchain
#
CONFIG_ARCH = CORTEXM3
+CONFIG_BOARD = PX4IO_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index fc87bedd5..2f70d001d 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
@@ -51,6 +54,7 @@ MODULES += systemcmds/esc_calib
MODULES += systemcmds/reboot
MODULES += systemcmds/top
MODULES += systemcmds/tests
+MODULES += systemcmds/config
#
# General system control
@@ -72,6 +76,7 @@ MODULES += examples/flow_position_estimator
#
# Vehicle Control
#
+MODULES += modules/segway
MODULES += modules/fixedwing_backside
MODULES += modules/fixedwing_att_control
MODULES += modules/fixedwing_pos_control
@@ -91,6 +96,7 @@ MODULES += modules/sdlog2
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/mathlib
+MODULES += modules/mathlib/math/filter
MODULES += modules/controllib
MODULES += modules/uORB
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index f1c1b496a..ecff77db9 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -153,6 +153,7 @@ ifeq ($(BOARD_FILE),)
$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
endif
export BOARD
+export BOARD_FILE
include $(BOARD_FILE)
$(info % BOARD = $(BOARD))
@@ -385,7 +386,7 @@ define BUILTIN_DEF
endef
# Don't generate until modules have updated their command files
-$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES)
+$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(MODULE_OBJS) $(MODULE_MKFILES) $(BUILTIN_COMMAND_FILES)
@$(ECHO) "CMDS: $@"
$(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
$(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
diff --git a/makefiles/module.mk b/makefiles/module.mk
index 9e4cbafc9..9c1a828cc 100644
--- a/makefiles/module.mk
+++ b/makefiles/module.mk
@@ -98,6 +98,7 @@
#
# CONFIG
# BOARD
+# BOARD_FILE
# MODULE_WORK_DIR
# MODULE_OBJ
# MODULE_MK
@@ -117,7 +118,7 @@ $(info %% MODULE_MK = $(MODULE_MK))
#
# Get the board/toolchain config
#
-include $(PX4_MK_DIR)/board_$(BOARD).mk
+include $(BOARD_FILE)
#
# Get the module's config
diff --git a/makefiles/setup.mk b/makefiles/setup.mk
index 92461fafb..168e41a5c 100644
--- a/makefiles/setup.mk
+++ b/makefiles/setup.mk
@@ -65,6 +65,7 @@ export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
export MKFW = $(PX4_BASE)/Tools/px_mkfw.py
export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
export COPY = cp
+export COPYDIR = cp -Rf
export REMOVE = rm -f
export RMDIR = rm -rf
export GENROMFS = genromfs
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index 3f4d3371a..9fd2dd516 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -85,6 +85,13 @@ ifeq ($(ARCHCPUFLAGS),)
$(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3)
endif
+# Set the board flags
+#
+ifeq ($(CONFIG_BOARD),)
+$(error Board config does not define CONFIG_BOARD)
+endif
+ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD)
+
# optimisation flags
#
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
diff --git a/makefiles/upload.mk b/makefiles/upload.mk
index 4b01b447d..3aebef863 100644
--- a/makefiles/upload.mk
+++ b/makefiles/upload.mk
@@ -27,8 +27,6 @@ all: upload-$(METHOD)-$(BOARD)
upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER)
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
-upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER)
- $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
#
# JTAG firmware uploading with OpenOCD
diff --git a/nuttx-configs/px4fmu-v1/include/board.h b/nuttx-configs/px4fmu-v1/include/board.h
new file mode 100644
index 000000000..839631b3a
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/include/board.h
@@ -0,0 +1,391 @@
+/************************************************************************************
+ * configs/stm32f4discovery/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
+#define __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+#include "stm32_rcc.h"
+#include "stm32_sdio.h"
+#include "stm32.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The PX4FMU uses a 24MHz crystal connected to the HSE.
+ *
+ * This is the canonical configuration:
+ * System Clock source : PLL (HSE)
+ * SYSCLK(Hz) : 168000000 Determined by PLL configuration
+ * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
+ * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
+ * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
+ * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
+ * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL)
+ * PLLM : 24 (STM32_PLLCFG_PLLM)
+ * PLLN : 336 (STM32_PLLCFG_PLLN)
+ * PLLP : 2 (STM32_PLLCFG_PLLP)
+ * PLLQ : 7 (STM32_PLLCFG_PLLQ)
+ * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
+ * Flash Latency(WS) : 5
+ * Prefetch Buffer : OFF
+ * Instruction cache : ON
+ * Data cache : ON
+ * Require 48MHz for USB OTG FS, : Enabled
+ * SDIO and RNG clock
+ */
+
+/* HSI - 16 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - On-board crystal frequency is 24MHz
+ * LSE - not installed
+ */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+//#define STM32_LSE_FREQUENCY 32768
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * = (8,000,000 / 8) * 336
+ * = 336,000,000
+ * SYSCLK = PLL_VCO / PLLP
+ * = 336,000,000 / 2 = 168,000,000
+ * USB OTG FS, SDIO and RNG Clock
+ * = PLL_VCO / PLLQ
+ * = 48,000,000
+ */
+
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
+#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
+
+#define STM32_SYSCLK_FREQUENCY 168000000ul
+
+/* AHB clock (HCLK) is SYSCLK (168MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
+
+/* Timers driven from APB1 will be twice PCLK1 */
+
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB2 will be twice PCLK2 */
+
+#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1
+ */
+
+#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
+#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
+
+/* High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/* LED definitions ******************************************************************/
+/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
+ * way. The following definitions are used to access individual LEDs.
+ */
+
+/* LED index values for use with stm32_setled() */
+
+#define BOARD_LED1 0
+#define BOARD_LED2 1
+#define BOARD_NLEDS 2
+
+#define BOARD_LED_BLUE BOARD_LED1
+#define BOARD_LED_RED BOARD_LED2
+
+/* LED bits for use with stm32_setleds() */
+
+#define BOARD_LED1_BIT (1 << BOARD_LED1)
+#define BOARD_LED2_BIT (1 << BOARD_LED2)
+
+/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 2 LEDs on board the
+ * px4fmu-v1. The following definitions describe how NuttX controls the LEDs:
+ */
+
+#define LED_STARTED 0 /* LED1 */
+#define LED_HEAPALLOCATE 1 /* LED2 */
+#define LED_IRQSENABLED 2 /* LED1 */
+#define LED_STACKCREATED 3 /* LED1 + LED2 */
+#define LED_INIRQ 4 /* LED1 */
+#define LED_SIGNAL 5 /* LED2 */
+#define LED_ASSERTION 6 /* LED1 + LED2 */
+#define LED_PANIC 7 /* LED1 + LED2 */
+
+/* Alternate function pin selections ************************************************/
+
+/*
+ * UARTs.
+ *
+ * Note that UART5 has no optional pinout, so it is not listed here.
+ */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_2
+
+#define GPIO_USART2_RX GPIO_USART2_RX_1
+#define GPIO_USART2_TX GPIO_USART2_TX_1
+#define GPIO_USART2_RTS GPIO_USART2_RTS_1
+#define GPIO_USART2_CTS GPIO_USART2_CTS_1
+
+#define GPIO_USART6_RX GPIO_USART6_RX_1
+#define GPIO_USART6_TX GPIO_USART6_TX_1
+
+/* UART DMA configuration for USART1/6 */
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
+
+/*
+ * PWM
+ *
+ * Four PWM outputs can be configured on pins otherwise shared with
+ * USART2; two can take the flow control pins if they are not being used.
+ *
+ * Pins:
+ *
+ * CTS - PA0 - TIM2CH1
+ * RTS - PA1 - TIM2CH2
+ * TX - PA2 - TIM2CH3
+ * RX - PA3 - TIM2CH4
+ *
+ */
+#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
+#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
+#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
+#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
+
+/*
+ * PPM
+ *
+ * PPM input is handled by the HRT timer.
+ */
+#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
+
+/*
+ * CAN
+ *
+ * CAN2 is routed to the expansion connector.
+ */
+
+#define GPIO_CAN2_RX GPIO_CAN2_RX_1
+#define GPIO_CAN2_TX GPIO_CAN2_TX_1
+
+/*
+ * I2C
+ *
+ * The optional _GPIO configurations allow the I2C driver to manually
+ * reset the bus to clear stuck slaves. They match the pin configuration,
+ * but are normally-high GPIOs.
+ */
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
+#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
+
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
+#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11)
+
+#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1
+#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1
+#define GPIO_I2C3_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN8)
+#define GPIO_I2C3_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
+
+/*
+ * I2C busses
+ */
+#define PX4_I2C_BUS_ESC 1
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_EXPANSION 3
+
+/*
+ * Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+#define PX4_I2C_OBDEV_MS5611 0x76
+#define PX4_I2C_OBDEV_EEPROM NOTDEFINED
+
+#define PX4_I2C_OBDEV_PX4IO_BL 0x18
+#define PX4_I2C_OBDEV_PX4IO 0x1a
+
+/*
+ * SPI
+ *
+ * There are sensors on SPI1, and SPI3 is connected to the microSD slot.
+ */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
+#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
+#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
+#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2
+
+/* SPI DMA configuration for SPI3 (microSD) */
+#define DMACHAN_SPI3_RX DMAMAP_SPI3_RX_1
+#define DMACHAN_SPI3_TX DMAMAP_SPI3_TX_2
+/* XXX since we allocate the HP work stack from CCM RAM on normal system startup,
+ SPI1 will never run in DMA mode - so we can just give it a random config here.
+ What we really need to do is to make DMA configurable per channel, and always
+ disable it for SPI1. */
+#define DMACHAN_SPI1_RX DMAMAP_SPI1_RX_1
+#define DMACHAN_SPI1_TX DMAMAP_SPI1_TX_2
+
+/*
+ * Use these in place of the spi_dev_e enumeration to
+ * select a specific SPI device on SPI1
+ */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL 2
+#define PX4_SPIDEV_MPU 3
+
+/*
+ * Optional devices on IO's external port
+ */
+#define PX4_SPIDEV_ACCEL_MAG 2
+
+/*
+ * Tone alarm output
+ */
+#define TONE_ALARM_TIMER 3 /* timer 3 */
+#define TONE_ALARM_CHANNEL 3 /* channel 3 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_ledinit, stm32_setled, and stm32_setleds
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
+ * CONFIG_ARCH_LEDS is not defined, then the following interfacesare available to
+ * control the LEDs from user applications.
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+EXTERN void stm32_ledinit(void);
+EXTERN void stm32_setled(int led, bool ledon);
+EXTERN void stm32_setleds(uint8_t ledset);
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIG_PX4FMU_V1_INCLUDE_BOARD_H */
diff --git a/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h
new file mode 100644
index 000000000..15e4e7a8d
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/include/nsh_romfsimg.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * nsh_romfsetc.h
+ *
+ * This file is a stub for 'make export' purposes; the actual ROMFS
+ * must be supplied by the library client.
+ */
+
+extern unsigned char romfs_img[];
+extern unsigned int romfs_img_len;
diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs
new file mode 100644
index 000000000..7b2ea703a
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs
@@ -0,0 +1,179 @@
+############################################################################
+# configs/px4fmu-v1/nsh/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+
+# enable precise stack overflow tracking
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
+EXTRA_LIBS += $(LIBM)
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-psabi
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
new file mode 100644
index 000000000..5b91930c9
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -0,0 +1,964 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+# CONFIG_HOST_LINUX is not set
+CONFIG_HOST_OSX=y
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+CONFIG_DEBUG_SYMBOLS=y
+
+#
+# System Type
+#
+# CONFIG_ARCH_8051 is not set
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+CONFIG_ARCH_CORTEXM4=y
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+CONFIG_ARCH_HAVE_FPU=y
+CONFIG_ARCH_FPU=y
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARMV7M_MPU is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+CONFIG_ARMV7M_TOOLCHAIN_GNU_EABI=y
+CONFIG_ARMV7M_STACKCHECK=y
+CONFIG_SERIAL_TERMIOS=y
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103RET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
+# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
+# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
+# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+CONFIG_ARCH_CHIP_STM32F405RG=y
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+# CONFIG_ARCH_CHIP_STM32F427V is not set
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+# CONFIG_STM32_STM32F10XX is not set
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+# CONFIG_STM32_PERFORMANCELINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+# CONFIG_STM32_MEDIUMDENSITY is not set
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F30XX is not set
+CONFIG_STM32_STM32F40XX=y
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+CONFIG_STM32_ADC1=y
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+CONFIG_STM32_BKPSRAM=y
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CAN2 is not set
+CONFIG_STM32_CCMDATARAM=y
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_CRYP is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_DCMI is not set
+# CONFIG_STM32_ETHMAC is not set
+# CONFIG_STM32_FSMC is not set
+# CONFIG_STM32_HASH is not set
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+CONFIG_STM32_I2C3=y
+CONFIG_STM32_OTGFS=y
+# CONFIG_STM32_OTGHS is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_RNG is not set
+# CONFIG_STM32_SDIO is not set
+CONFIG_STM32_SPI1=y
+# CONFIG_STM32_SPI2 is not set
+CONFIG_STM32_SPI3=y
+CONFIG_STM32_SYSCFG=y
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+CONFIG_STM32_TIM4=y
+CONFIG_STM32_TIM5=y
+CONFIG_STM32_TIM6=y
+CONFIG_STM32_TIM7=y
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_TIM9=y
+CONFIG_STM32_TIM10=y
+CONFIG_STM32_TIM11=y
+CONFIG_STM32_TIM12=y
+CONFIG_STM32_TIM13=y
+CONFIG_STM32_TIM14=y
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+CONFIG_STM32_UART5=y
+CONFIG_STM32_USART6=y
+# CONFIG_STM32_IWDG is not set
+CONFIG_STM32_WWDG=y
+CONFIG_STM32_ADC=y
+CONFIG_STM32_SPI=y
+CONFIG_STM32_I2C=y
+
+#
+# Alternate Pin Mapping
+#
+CONFIG_STM32_FLASH_PREFETCH=y
+# CONFIG_STM32_JTAG_DISABLE is not set
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_CCMEXCLUDE is not set
+CONFIG_STM32_DMACAPABLE=y
+# CONFIG_STM32_TIM4_PWM is not set
+# CONFIG_STM32_TIM5_PWM is not set
+# CONFIG_STM32_TIM9_PWM is not set
+# CONFIG_STM32_TIM10_PWM is not set
+# CONFIG_STM32_TIM11_PWM is not set
+# CONFIG_STM32_TIM12_PWM is not set
+# CONFIG_STM32_TIM13_PWM is not set
+# CONFIG_STM32_TIM14_PWM is not set
+# CONFIG_STM32_TIM4_ADC is not set
+# CONFIG_STM32_TIM5_ADC is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+# CONFIG_USART1_RXDMA is not set
+# CONFIG_USART2_RS485 is not set
+CONFIG_USART2_RXDMA=y
+# CONFIG_USART3_RXDMA is not set
+# CONFIG_UART4_RXDMA is not set
+# CONFIG_UART5_RS485 is not set
+CONFIG_UART5_RXDMA=y
+# CONFIG_USART6_RS485 is not set
+CONFIG_USART6_RXDMA=y
+# CONFIG_USART7_RXDMA is not set
+# CONFIG_USART8_RXDMA is not set
+CONFIG_SERIAL_DISABLE_REORDERING=y
+CONFIG_STM32_USART_SINGLEWIRE=y
+
+#
+# SPI Configuration
+#
+# CONFIG_STM32_SPI_INTERRUPTS is not set
+# CONFIG_STM32_SPI_DMA is not set
+
+#
+# I2C Configuration
+#
+# CONFIG_STM32_I2C_DYNTIMEO is not set
+CONFIG_STM32_I2CTIMEOSEC=0
+CONFIG_STM32_I2CTIMEOMS=10
+CONFIG_STM32_I2CTIMEOTICKS=500
+# CONFIG_STM32_I2C_DUTY16_9 is not set
+
+#
+# USB Host Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# External Memory Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_IRQPRIO=y
+# CONFIG_CUSTOM_STACK is not set
+# CONFIG_ADDRENV is not set
+CONFIG_ARCH_HAVE_VFORK=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=16717
+# CONFIG_ARCH_CALIBRATION is not set
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_SIZE=196608
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=2048
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_CUSTOM=y
+CONFIG_ARCH_BOARD=""
+
+#
+# Common Board Options
+#
+CONFIG_NSH_MMCSDMINOR=0
+CONFIG_NSH_MMCSDSLOTNO=0
+CONFIG_NSH_MMCSDSPIPORTNO=3
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_BOARD_INITIALIZE is not set
+CONFIG_MSEC_PER_TICK=1
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_TASK_NAME_SIZE=24
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+# CONFIG_DEV_CONSOLE is not set
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=8
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WAITPID=y
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+# CONFIG_SCHED_ONEXIT is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_DISABLE_OS_API=y
+# CONFIG_DISABLE_CLOCK is not set
+# CONFIG_DISABLE_POSIX_TIMERS is not set
+# CONFIG_DISABLE_PTHREAD is not set
+# CONFIG_DISABLE_SIGNALS is not set
+# CONFIG_DISABLE_MQUEUE is not set
+# CONFIG_DISABLE_ENVIRON is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+CONFIG_SIG_SIGWORK=4
+
+#
+# Sizes of configurable things (0 disables)
+#
+CONFIG_MAX_TASKS=32
+CONFIG_MAX_TASK_ARGS=10
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=32
+CONFIG_NFILE_STREAMS=25
+CONFIG_NAME_MAX=32
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=50
+CONFIG_PREALLOC_TIMERS=50
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=6000
+CONFIG_USERMAIN_STACKSIZE=4096
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+CONFIG_DEV_NULL=y
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_PWM is not set
+CONFIG_I2C=y
+# CONFIG_I2C_SLAVE is not set
+CONFIG_I2C_TRANSFER=y
+# CONFIG_I2C_WRITEREAD is not set
+# CONFIG_I2C_POLLED is not set
+# CONFIG_I2C_TRACE is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+CONFIG_I2C_RESET=y
+CONFIG_SPI=y
+# CONFIG_SPI_OWNBUS is not set
+CONFIG_SPI_EXCHANGE=y
+# CONFIG_SPI_CMDDATA is not set
+# CONFIG_RTC is not set
+CONFIG_WATCHDOG=y
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+CONFIG_MMCSD=y
+CONFIG_MMCSD_NSLOTS=1
+# CONFIG_MMCSD_READONLY is not set
+# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
+# CONFIG_MMCSD_MMCSUPPORT is not set
+# CONFIG_MMCSD_HAVECARDDETECT is not set
+CONFIG_MMCSD_SPI=y
+CONFIG_MMCSD_SPICLOCK=24000000
+# CONFIG_MMCSD_SDIO is not set
+# CONFIG_MTD is not set
+CONFIG_PIPES=y
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+CONFIG_SERIAL_REMOVABLE=y
+# CONFIG_16550_UART is not set
+CONFIG_ARCH_HAVE_UART5=y
+CONFIG_ARCH_HAVE_USART1=y
+CONFIG_ARCH_HAVE_USART2=y
+CONFIG_ARCH_HAVE_USART6=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_USART1_SERIAL_CONSOLE is not set
+# CONFIG_USART2_SERIAL_CONSOLE is not set
+# CONFIG_UART5_SERIAL_CONSOLE is not set
+# CONFIG_USART6_SERIAL_CONSOLE is not set
+CONFIG_NO_SERIAL_CONSOLE=y
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=512
+CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+
+#
+# USART2 Configuration
+#
+CONFIG_USART2_RXBUFSIZE=512
+CONFIG_USART2_TXBUFSIZE=512
+CONFIG_USART2_BAUD=57600
+CONFIG_USART2_BITS=8
+CONFIG_USART2_PARITY=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART2_IFLOWCONTROL=y
+CONFIG_USART2_OFLOWCONTROL=y
+
+#
+# UART5 Configuration
+#
+CONFIG_UART5_RXBUFSIZE=32
+CONFIG_UART5_TXBUFSIZE=32
+CONFIG_UART5_BAUD=57600
+CONFIG_UART5_BITS=8
+CONFIG_UART5_PARITY=0
+CONFIG_UART5_2STOP=0
+# CONFIG_UART5_IFLOWCONTROL is not set
+# CONFIG_UART5_OFLOWCONTROL is not set
+
+#
+# USART6 Configuration
+#
+CONFIG_USART6_RXBUFSIZE=512
+CONFIG_USART6_TXBUFSIZE=512
+CONFIG_USART6_BAUD=57600
+CONFIG_USART6_BITS=8
+CONFIG_USART6_PARITY=0
+CONFIG_USART6_2STOP=0
+# CONFIG_USART6_IFLOWCONTROL is not set
+# CONFIG_USART6_OFLOWCONTROL is not set
+CONFIG_SERIAL_IFLOWCONTROL=y
+CONFIG_SERIAL_OFLOWCONTROL=y
+CONFIG_USBDEV=y
+
+#
+# USB Device Controller Driver Options
+#
+# CONFIG_USBDEV_ISOCHRONOUS is not set
+# CONFIG_USBDEV_DUALSPEED is not set
+# CONFIG_USBDEV_SELFPOWERED is not set
+CONFIG_USBDEV_BUSPOWERED=y
+CONFIG_USBDEV_MAXPOWER=500
+# CONFIG_USBDEV_REMOTEWAKEUP is not set
+# CONFIG_USBDEV_DMA is not set
+# CONFIG_USBDEV_TRACE is not set
+
+#
+# USB Device Class Driver Options
+#
+# CONFIG_USBDEV_COMPOSITE is not set
+# CONFIG_PL2303 is not set
+CONFIG_CDCACM=y
+CONFIG_CDCACM_CONSOLE=y
+CONFIG_CDCACM_EP0MAXPACKET=64
+CONFIG_CDCACM_EPINTIN=1
+CONFIG_CDCACM_EPINTIN_FSSIZE=64
+CONFIG_CDCACM_EPINTIN_HSSIZE=64
+CONFIG_CDCACM_EPBULKOUT=3
+CONFIG_CDCACM_EPBULKOUT_FSSIZE=64
+CONFIG_CDCACM_EPBULKOUT_HSSIZE=512
+CONFIG_CDCACM_EPBULKIN=2
+CONFIG_CDCACM_EPBULKIN_FSSIZE=64
+CONFIG_CDCACM_EPBULKIN_HSSIZE=512
+CONFIG_CDCACM_NWRREQS=4
+CONFIG_CDCACM_NRDREQS=4
+CONFIG_CDCACM_BULKIN_REQLEN=96
+CONFIG_CDCACM_RXBUFSIZE=256
+CONFIG_CDCACM_TXBUFSIZE=256
+CONFIG_CDCACM_VENDORID=0x26ac
+CONFIG_CDCACM_PRODUCTID=0x0010
+CONFIG_CDCACM_VENDORSTR="3D Robotics"
+CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.x"
+# CONFIG_USBMSC is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+
+#
+# Networking Support
+#
+# CONFIG_NET is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_RAMMAP is not set
+CONFIG_FS_FAT=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
+CONFIG_FAT_MAXFNAME=32
+CONFIG_FS_FATTIME=y
+# CONFIG_FAT_DMAMEMORY is not set
+CONFIG_FS_NXFFS=y
+CONFIG_NXFFS_PREALLOCATED=y
+CONFIG_NXFFS_ERASEDSTATE=0xff
+CONFIG_NXFFS_PACKTHRESHOLD=32
+CONFIG_NXFFS_MAXNAMLEN=32
+CONFIG_NXFFS_TAILTHRESHOLD=2048
+CONFIG_FS_ROMFS=y
+# CONFIG_FS_SMARTFS is not set
+CONFIG_FS_BINFS=y
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG_ENABLE is not set
+CONFIG_SYSLOG=y
+CONFIG_SYSLOG_CHAR=y
+CONFIG_SYSLOG_DEVPATH="/dev/ttyS0"
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+# CONFIG_MM_MULTIHEAP is not set
+# CONFIG_MM_SMALL is not set
+CONFIG_MM_REGIONS=2
+CONFIG_GRAN=y
+CONFIG_GRAN_SINGLE=y
+CONFIG_GRAN_INTR=y
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Formats
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+# CONFIG_SYMTAB_ORDEREDBYNAME is not set
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=256
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=1024
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=2048
+CONFIG_LIBC_STRERROR=y
+# CONFIG_LIBC_STRERROR_SHORT is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_LIB_SENDFILE_BUFSIZE=512
+# CONFIG_ARCH_ROMGETC is not set
+CONFIG_ARCH_OPTIMIZED_FUNCTIONS=y
+CONFIG_ARCH_MEMCPY=y
+# CONFIG_ARCH_MEMCMP is not set
+# CONFIG_ARCH_MEMMOVE is not set
+# CONFIG_ARCH_MEMSET is not set
+# CONFIG_MEMSET_OPTSPEED is not set
+# CONFIG_ARCH_STRCHR is not set
+# CONFIG_ARCH_STRCMP is not set
+# CONFIG_ARCH_STRCPY is not set
+# CONFIG_ARCH_STRNCPY is not set
+# CONFIG_ARCH_STRLEN is not set
+# CONFIG_ARCH_STRNLEN is not set
+# CONFIG_ARCH_BZERO is not set
+
+#
+# Non-standard Library Support
+#
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_WORKPRIORITY=192
+CONFIG_SCHED_WORKPERIOD=5000
+CONFIG_SCHED_WORKSTACKSIZE=2048
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKPERIOD=50000
+CONFIG_SCHED_LPWORKSTACKSIZE=2048
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+# CONFIG_C99_BOOL8 is not set
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=1024
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+CONFIG_EXAMPLES_CDCACM=y
+# CONFIG_EXAMPLES_COMPOSITE is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_LCDRW is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+CONFIG_EXAMPLES_MOUNT=y
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NULL is not set
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXCONSOLE is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PASHELLO is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_UDP is not set
+# CONFIG_EXAMPLES_UIP is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBMSC is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_DHCPC is not set
+# CONFIG_NETUTILS_DHCPD is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_FTPD is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_RESOLV is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TELNETD is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_UIPLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+# CONFIG_NSH_DISABLE_CAT is not set
+# CONFIG_NSH_DISABLE_CD is not set
+# CONFIG_NSH_DISABLE_CP is not set
+# CONFIG_NSH_DISABLE_DD is not set
+# CONFIG_NSH_DISABLE_ECHO is not set
+# CONFIG_NSH_DISABLE_EXEC is not set
+# CONFIG_NSH_DISABLE_EXIT is not set
+# CONFIG_NSH_DISABLE_FREE is not set
+# CONFIG_NSH_DISABLE_GET is not set
+# CONFIG_NSH_DISABLE_HELP is not set
+# CONFIG_NSH_DISABLE_HEXDUMP is not set
+# CONFIG_NSH_DISABLE_IFCONFIG is not set
+# CONFIG_NSH_DISABLE_KILL is not set
+# CONFIG_NSH_DISABLE_LOSETUP is not set
+# CONFIG_NSH_DISABLE_LS is not set
+# CONFIG_NSH_DISABLE_MB is not set
+# CONFIG_NSH_DISABLE_MKDIR is not set
+# CONFIG_NSH_DISABLE_MKFATFS is not set
+# CONFIG_NSH_DISABLE_MKFIFO is not set
+# CONFIG_NSH_DISABLE_MKRD is not set
+# CONFIG_NSH_DISABLE_MH is not set
+# CONFIG_NSH_DISABLE_MOUNT is not set
+# CONFIG_NSH_DISABLE_MW is not set
+# CONFIG_NSH_DISABLE_NSFMOUNT is not set
+# CONFIG_NSH_DISABLE_PS is not set
+# CONFIG_NSH_DISABLE_PING is not set
+# CONFIG_NSH_DISABLE_PUT is not set
+# CONFIG_NSH_DISABLE_PWD is not set
+# CONFIG_NSH_DISABLE_RM is not set
+# CONFIG_NSH_DISABLE_RMDIR is not set
+# CONFIG_NSH_DISABLE_SET is not set
+# CONFIG_NSH_DISABLE_SH is not set
+# CONFIG_NSH_DISABLE_SLEEP is not set
+# CONFIG_NSH_DISABLE_TEST is not set
+# CONFIG_NSH_DISABLE_UMOUNT is not set
+# CONFIG_NSH_DISABLE_UNSET is not set
+# CONFIG_NSH_DISABLE_USLEEP is not set
+# CONFIG_NSH_DISABLE_WGET is not set
+# CONFIG_NSH_DISABLE_XD is not set
+
+#
+# Configure Command Options
+#
+# CONFIG_NSH_CMDOPT_DF_H is not set
+CONFIG_NSH_CODECS_BUFSIZE=128
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_MAXARGUMENTS=12
+CONFIG_NSH_NESTDEPTH=8
+# CONFIG_NSH_DISABLESCRIPT is not set
+# CONFIG_NSH_DISABLEBG is not set
+CONFIG_NSH_ROMFSETC=y
+# CONFIG_NSH_ROMFSRC is not set
+CONFIG_NSH_ROMFSMOUNTPT="/etc"
+CONFIG_NSH_INITSCRIPT="init.d/rcS"
+CONFIG_NSH_ROMFSDEVNO=0
+CONFIG_NSH_ROMFSSECTSIZE=128
+CONFIG_NSH_ARCHROMFS=y
+CONFIG_NSH_FATDEVNO=1
+CONFIG_NSH_FATSECTSIZE=512
+CONFIG_NSH_FATNSECTORS=1024
+CONFIG_NSH_FATMOUNTPT="/tmp"
+CONFIG_NSH_CONSOLE=y
+# CONFIG_NSH_USBCONSOLE is not set
+
+#
+# USB Trace Support
+#
+# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# System NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# I2C tool
+#
+# CONFIG_SYSTEM_I2CTOOL is not set
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sysinfo
+#
+CONFIG_SYSTEM_SYSINFO=y
+
+#
+# USB Monitor
+#
diff --git a/nuttx-configs/px4fmu-v1/nsh/setenv.sh b/nuttx-configs/px4fmu-v1/nsh/setenv.sh
new file mode 100755
index 000000000..db372217c
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/nsh/setenv.sh
@@ -0,0 +1,75 @@
+#!/bin/bash
+# configs/px4fmu-v1/usbnsh/setenv.sh
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script
new file mode 100644
index 000000000..ced5b21b7
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/scripts/ld.script
@@ -0,0 +1,149 @@
+/****************************************************************************
+ * configs/px4fmu-v1/scripts/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F405RG has 1024Kb of FLASH beginning at address 0x0800:0000 and
+ * 192Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of CCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param*))
+ __param_end = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx-configs/px4fmu-v1/src/Makefile b/nuttx-configs/px4fmu-v1/src/Makefile
new file mode 100644
index 000000000..6ef8b7d6a
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/px4fmu-v1/src/Makefile
+#
+# Copyright (C) 2013 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = empty.c
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
+
diff --git a/nuttx-configs/px4fmu-v1/src/empty.c b/nuttx-configs/px4fmu-v1/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx-configs/px4fmu-v1/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx-configs/px4io-v1/include/README.txt b/nuttx-configs/px4io-v1/include/README.txt
new file mode 100755
index 000000000..2264a80aa
--- /dev/null
+++ b/nuttx-configs/px4io-v1/include/README.txt
@@ -0,0 +1 @@
+This directory contains header files unique to the PX4IO board.
diff --git a/nuttx-configs/px4io-v1/include/board.h b/nuttx-configs/px4io-v1/include/board.h
new file mode 100755
index 000000000..6503a94cd
--- /dev/null
+++ b/nuttx-configs/px4io-v1/include/board.h
@@ -0,0 +1,168 @@
+/************************************************************************************
+ * configs/px4io/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ * Copyright (C) 2012 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+# include <stdbool.h>
+#endif
+#include <stm32_rcc.h>
+#include <stm32_sdio.h>
+#include <stm32.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+
+/* On-board crystal frequency is 24MHz (HSE) */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+/* Use the HSE output as the system clock */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_HSE
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_HSE
+#define STM32_SYSCLK_FREQUENCY STM32_BOARD_XTAL
+
+/* AHB clock (HCLK) is SYSCLK (24MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-4 */
+
+/* APB2 timer 1 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK (24MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY)
+
+/* All timers run off PCLK */
+
+#define STM32_APB1_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB1_TIM2_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/*
+ * Some of the USART pins are not available; override the GPIO
+ * definitions with an invalid pin configuration.
+ */
+#undef GPIO_USART2_CTS
+#define GPIO_USART2_CTS 0xffffffff
+#undef GPIO_USART2_RTS
+#define GPIO_USART2_RTS 0xffffffff
+#undef GPIO_USART2_CK
+#define GPIO_USART2_CK 0xffffffff
+#undef GPIO_USART3_TX
+#define GPIO_USART3_TX 0xffffffff
+#undef GPIO_USART3_CK
+#define GPIO_USART3_CK 0xffffffff
+#undef GPIO_USART3_CTS
+#define GPIO_USART3_CTS 0xffffffff
+#undef GPIO_USART3_RTS
+#define GPIO_USART3_RTS 0xffffffff
+
+/*
+ * High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
+
+/*
+ * PPM
+ *
+ * PPM input is handled by the HRT timer.
+ *
+ * Pin is PA8, timer 1, channel 1
+ */
+#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
+#define GPIO_PPM_IN GPIO_TIM1_CH1IN
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs
new file mode 100644
index 000000000..712631f47
--- /dev/null
+++ b/nuttx-configs/px4io-v1/nsh/Make.defs
@@ -0,0 +1,166 @@
+############################################################################
+# configs/px4io-v1/nsh/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m3 \
+ -mthumb \
+ -march=armv7-m
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/copydir.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+EXTRA_LIBS += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx-configs/px4io-v1/nsh/appconfig b/nuttx-configs/px4io-v1/nsh/appconfig
new file mode 100644
index 000000000..48a41bcdb
--- /dev/null
+++ b/nuttx-configs/px4io-v1/nsh/appconfig
@@ -0,0 +1,32 @@
+############################################################################
+#
+# Copyright (C) 2012 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.
+#
+############################################################################
diff --git a/nuttx-configs/px4io-v1/nsh/defconfig b/nuttx-configs/px4io-v1/nsh/defconfig
new file mode 100755
index 000000000..3785e0367
--- /dev/null
+++ b/nuttx-configs/px4io-v1/nsh/defconfig
@@ -0,0 +1,537 @@
+############################################################################
+# configs/px4io-v1/nsh/defconfig
+#
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+############################################################################
+#
+# architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_family - for use in C code. This identifies the
+# particular chip family that the architecture is implemented
+# in.
+# CONFIG_ARCH_architecture - for use in C code. This identifies the
+# specific architecture within the chip family.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
+# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+# stack. If defined, this symbol is the size of the interrupt
+# stack in bytes. If not defined, the user task stacks will be
+# used during interrupt handling.
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
+# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+# cause a 100 second delay during boot-up. This 100 second delay
+# serves no purpose other than it allows you to calibrate
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
+# the delay actually is 100 seconds.
+# CONFIG_ARCH_DMA - Support DMA initialization
+#
+CONFIG_ARCH="arm"
+CONFIG_ARCH_ARM=y
+CONFIG_ARCH_CORTEXM3=y
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARCH_CHIP_STM32F100C8=y
+#
+# Board Selection
+#
+CONFIG_ARCH_BOARD_PX4IO_V1=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="px4io-v1"
+CONFIG_BOARD_LOOPSPERMSEC=2000
+CONFIG_DRAM_SIZE=0x00002000
+CONFIG_DRAM_START=0x20000000
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_LEDS=n
+CONFIG_ARCH_BUTTONS=n
+CONFIG_ARCH_CALIBRATION=n
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_MATH_H=y
+
+CONFIG_ARMV7M_CMNVECTOR=y
+# CONFIG_ARMV7M_STACKCHECK is not set
+
+#
+# JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+#
+# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG
+#
+# JTAG Enable options:
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# but without JNTRST.
+# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+#
+CONFIG_STM32_DFU=n
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# Individual subsystems can be enabled:
+#
+# AHB:
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=n
+CONFIG_STM32_CRC=n
+# APB1:
+# Timers 2,3 and 4 are owned by the PWM driver
+CONFIG_STM32_TIM2=n
+CONFIG_STM32_TIM3=n
+CONFIG_STM32_TIM4=n
+CONFIG_STM32_TIM5=n
+CONFIG_STM32_TIM6=n
+CONFIG_STM32_TIM7=n
+CONFIG_STM32_WWDG=n
+CONFIG_STM32_SPI2=n
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=n
+CONFIG_STM32_BKP=n
+CONFIG_STM32_PWR=n
+CONFIG_STM32_DAC=n
+# APB2:
+# We use our own ADC driver, but leave this on for clocking purposes.
+CONFIG_STM32_ADC1=y
+CONFIG_STM32_ADC2=n
+# TIM1 is owned by the HRT
+CONFIG_STM32_TIM1=n
+CONFIG_STM32_SPI1=n
+CONFIG_STM32_TIM8=n
+CONFIG_STM32_USART1=y
+CONFIG_STM32_ADC3=n
+
+
+#
+# STM32F100 specific serial device driver settings
+#
+# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
+# console and ttys0 (default is the USART1).
+# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
+# This specific the size of the receive buffer
+# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
+# being sent. This specific the size of the transmit buffer
+# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_USARTn_2STOP - Two stop bits
+#
+CONFIG_SERIAL_TERMIOS=y
+CONFIG_STANDARD_SERIAL=y
+
+CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART2_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=n
+
+CONFIG_USART1_TXBUFSIZE=64
+CONFIG_USART2_TXBUFSIZE=64
+CONFIG_USART3_TXBUFSIZE=64
+
+CONFIG_USART1_RXBUFSIZE=64
+CONFIG_USART2_RXBUFSIZE=64
+CONFIG_USART3_RXBUFSIZE=64
+
+CONFIG_USART1_BAUD=115200
+CONFIG_USART2_BAUD=115200
+CONFIG_USART3_BAUD=115200
+
+CONFIG_USART1_BITS=8
+CONFIG_USART2_BITS=8
+CONFIG_USART3_BITS=8
+
+CONFIG_USART1_PARITY=0
+CONFIG_USART2_PARITY=0
+CONFIG_USART3_PARITY=0
+
+CONFIG_USART1_2STOP=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART3_2STOP=0
+
+CONFIG_USART1_RXDMA=y
+SERIAL_HAVE_CONSOLE_DMA=y
+# Conflicts with I2C1 DMA
+CONFIG_USART2_RXDMA=n
+CONFIG_USART3_RXDMA=y
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com using the tools/mkimage.sh script
+# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_RAW_BINARY - make a raw binary format file used with many
+# different loaders using the GNU objcopy program. This option
+# should not be selected if you are not using the GNU toolchain.
+# CONFIG_HAVE_LIBM - toolchain supports libm.a
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=n
+CONFIG_MOTOROLA_SREC=n
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=n
+
+#
+# General OS setup
+#
+# CONFIG_APPS_DIR - Identifies the relative path to the directory
+# that builds the application to link with NuttX. Default: ../apps
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_DEBUG_SYMBOLS - build without optimization and with
+# debug symbols (needed for use with a debugger).
+# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
+# or MSEC_PER_TICK=10. This setting may be defined to
+# inform NuttX that the processor hardware is providing
+# system timer interrupts at some interrupt interval other
+# than 10 msec.
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
+# You would only need this if you are concerned about accurate
+# time conversions in the past or in the distant future.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
+# would only need this if you are concerned about accurate
+# time conversion in the distand past. You must also define
+# CONFIG_GREGORIAN_TIME in order to use Julian time.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
+# driver (minimul support)
+# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
+# errorcheck mutexes. Enables pthread_mutexattr_settype().
+# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
+# inheritance on mutexes and semaphores.
+# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
+# inheritance is enabled. It defines the maximum number of
+# different threads (minus one) that can take counts on a
+# semaphore with priority inheritance support. This may be
+# set to zero if priority inheritance is disabled OR if you
+# are only using semaphores as mutexes (only one holder) OR
+# if no more than two threads participate using a counting
+# semaphore.
+# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
+# then this setting is the maximum number of higher priority
+# threads (minus 1) than can be waiting for another thread
+# to release a count on a semaphore. This value may be set
+# to zero if no more than one thread is expected to wait for
+# a semaphore.
+# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
+# by task_create() when a new task is started. If set, all
+# files/drivers will appear to be closed in the new task.
+# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
+# three file descriptors (stdin, stdout, stderr) by task_create()
+# when a new task is started. If set, all files/drivers will
+# appear to be closed in the new task except for stdin, stdout,
+# and stderr.
+# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
+# desciptors by task_create() when a new task is started. If
+# set, all sockets will appear to be closed in the new task.
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work in units of microseconds. Default: 50*1000 (50 MS).
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
+#
+CONFIG_USER_ENTRYPOINT="user_start"
+#CONFIG_APPS_DIR=
+CONFIG_DEBUG=n
+CONFIG_DEBUG_VERBOSE=n
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
+CONFIG_MSEC_PER_TICK=1
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+CONFIG_MM_REGIONS=1
+CONFIG_MM_SMALL=y
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_RR_INTERVAL=0
+CONFIG_SCHED_INSTRUMENTATION=n
+CONFIG_TASK_NAME_SIZE=8
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_GREGORIAN_TIME=n
+CONFIG_JULIAN_TIME=n
+# this eats ~1KiB of RAM ... work out why
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=n
+CONFIG_MUTEX_TYPES=n
+CONFIG_PRIORITY_INHERITANCE=n
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=0
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=50000
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=n
+CONFIG_SCHED_ATEXIT=n
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=n
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_ENVIRON=y
+CONFIG_DISABLE_POLL=y
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve system performance
+#
+CONFIG_ARCH_MEMCPY=n
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_STRNLEN=n
+CONFIG_ARCH_BZERO=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=4
+CONFIG_MAX_TASK_ARGS=4
+CONFIG_NPTHREAD_KEYS=2
+CONFIG_NFILE_DESCRIPTORS=8
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=12
+CONFIG_STDIO_BUFFER_SIZE=32
+CONFIG_STDIO_LINEBUFFER=n
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_PREALLOC_TIMERS=0
+
+
+#
+# Settings for apps/nshlib
+#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
+# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
+# CONFIG_NSH_STRERROR - Use strerror(errno)
+# CONFIG_NSH_LINELEN - Maximum length of one command line
+# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
+# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
+# CONFIG_NSH_DISABLEBG - Disable background commands
+# CONFIG_NSH_ROMFSETC - Use startup script in /etc
+# CONFIG_NSH_CONSOLE - Use serial console front end
+# CONFIG_NSH_TELNET - Use telnetd console front end
+# CONFIG_NSH_ARCHINIT - Platform provides architecture
+# specific initialization (nsh_archinitialize()).
+#
+
+# Disable NSH completely
+CONFIG_NSH_CONSOLE=n
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
+# operation from FLASH but must copy initialized .data sections to RAM.
+# (should also be =n for the STM3210E-EVAL which always runs from flash)
+# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
+# but copy themselves entirely into RAM for better performance.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
+# This is the thread that (1) performs the inital boot of the system up
+# to the point where user_start() is spawned, and (2) there after is the
+# IDLE thread that executes only when there is no other thread ready to
+# run.
+# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
+# for the main user thread that begins at the user_start() entry point.
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=1200
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=1024
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
+
+#
+# NSH Library
+#
+# CONFIG_NSH_LIBRARY is not set
+# CONFIG_NSH_BUILTIN_APPS is not set
diff --git a/nuttx-configs/px4io-v1/nsh/setenv.sh b/nuttx-configs/px4io-v1/nsh/setenv.sh
new file mode 100755
index 000000000..ff9a4bf8a
--- /dev/null
+++ b/nuttx-configs/px4io-v1/nsh/setenv.sh
@@ -0,0 +1,47 @@
+#!/bin/bash
+# configs/stm3210e-eval/dfu/setenv.sh
+#
+# Copyright (C) 2009 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# 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 NuttX 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.
+#
+
+if [ "$(basename $0)" = "setenv.sh" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
+
+WD=`pwd`
+export RIDE_BIN="/cygdrive/c/Program Files/Raisonance/Ride/arm-gcc/bin"
+export BUILDROOT_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+export PATH="${BUILDROOT_BIN}:${RIDE_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4io-v1/scripts/ld.script b/nuttx-configs/px4io-v1/scripts/ld.script
new file mode 100755
index 000000000..69c2f9cb2
--- /dev/null
+++ b/nuttx-configs/px4io-v1/scripts/ld.script
@@ -0,0 +1,129 @@
+/****************************************************************************
+ * configs/stm3210e-eval/nsh/ld.script
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/* The STM32F100C8 has 64Kb of FLASH beginning at address 0x0800:0000 and
+ * 8Kb of SRAM beginning at address 0x2000:0000. When booting from FLASH,
+ * FLASH memory is aliased to address 0x0000:0000 where the code expects to
+ * begin execution by jumping to the entry point in the 0x0800:0000 address
+ * range.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08001000, LENGTH = 60K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K
+}
+
+OUTPUT_ARCH(arm)
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ /* The STM32F100CB has 8Kb of SRAM beginning at the following address */
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx-configs/px4io-v1/src/Makefile b/nuttx-configs/px4io-v1/src/Makefile
new file mode 100644
index 000000000..bb9539d16
--- /dev/null
+++ b/nuttx-configs/px4io-v1/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/stm3210e-eval/src/Makefile
+#
+# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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 NuttX 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.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = empty.c
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx-configs/px4io-v1/src/empty.c b/nuttx-configs/px4io-v1/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx-configs/px4io-v1/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
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/device/cdev.cpp b/src/drivers/device/cdev.cpp
index 422321850..47ebcd40a 100644
--- a/src/drivers/device/cdev.cpp
+++ b/src/drivers/device/cdev.cpp
@@ -111,21 +111,21 @@ CDev::~CDev()
int
CDev::init()
{
- int ret = OK;
-
// base class init first
- ret = Device::init();
+ int ret = Device::init();
if (ret != OK)
goto out;
// now register the driver
- ret = register_driver(_devname, &fops, 0666, (void *)this);
+ if (_devname != nullptr) {
+ ret = register_driver(_devname, &fops, 0666, (void *)this);
- if (ret != OK)
- goto out;
+ if (ret != OK)
+ goto out;
- _registered = true;
+ _registered = true;
+ }
out:
return ret;
@@ -395,4 +395,4 @@ cdev_poll(struct file *filp, struct pollfd *fds, bool setup)
return cdev->poll(filp, fds, setup);
}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 04a5222c3..c3ee77b1c 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -223,5 +223,22 @@ interrupt(int irq, void *context)
return OK;
}
+int
+Device::read(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::write(unsigned offset, void *data, unsigned count)
+{
+ return -ENODEV;
+}
+
+int
+Device::ioctl(unsigned operation, unsigned &arg)
+{
+ return -ENODEV;
+}
-} // namespace device \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index 7d375aab9..a9ed5d77c 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -69,10 +69,61 @@ class __EXPORT Device
{
public:
/**
+ * Destructor.
+ *
+ * Public so that anonymous devices can be destroyed.
+ */
+ virtual ~Device();
+
+ /**
* Interrupt handler.
*/
virtual void interrupt(void *ctx); /**< interrupt handler */
+ /*
+ * Direct access methods.
+ */
+
+ /**
+ * Initialise the driver and make it ready for use.
+ *
+ * @return OK if the driver initialized OK, negative errno otherwise;
+ */
+ virtual int init();
+
+ /**
+ * Read directly from the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param offset The device address at which to start reading
+ * @param data The buffer into which the read values should be placed.
+ * @param count The number of items to read.
+ * @return The number of items read on success, negative errno otherwise.
+ */
+ virtual int read(unsigned address, void *data, unsigned count);
+
+ /**
+ * Write directly to the device.
+ *
+ * The actual size of each unit quantity is device-specific.
+ *
+ * @param address The device address at which to start writing.
+ * @param data The buffer from which values should be read.
+ * @param count The number of items to write.
+ * @return The number of items written on success, negative errno otherwise.
+ */
+ virtual int write(unsigned address, void *data, unsigned count);
+
+ /**
+ * Perform a device-specific operation.
+ *
+ * @param operation The operation to perform.
+ * @param arg An argument to the operation.
+ * @return Negative errno on error, OK or positive value on success.
+ */
+ virtual int ioctl(unsigned operation, unsigned &arg);
+
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
@@ -85,14 +136,6 @@ protected:
*/
Device(const char *name,
int irq = 0);
- ~Device();
-
- /**
- * Initialise the driver and make it ready for use.
- *
- * @return OK if the driver initialised OK.
- */
- virtual int init();
/**
* Enable the device interrupt
@@ -189,7 +232,7 @@ public:
/**
* Destructor
*/
- ~CDev();
+ virtual ~CDev();
virtual int init();
@@ -282,6 +325,7 @@ public:
* Test whether the device is currently open.
*
* This can be used to avoid tearing down a device that is still active.
+ * Note - not virtual, cannot be overridden by a subclass.
*
* @return True if the device is currently open.
*/
@@ -396,9 +440,9 @@ public:
const char *devname,
uint32_t base,
int irq = 0);
- ~PIO();
+ virtual ~PIO();
- int init();
+ virtual int init();
protected:
@@ -407,7 +451,7 @@ protected:
*
* @param offset Register offset in bytes from the base address.
*/
- uint32_t reg(uint32_t offset) {
+ uint32_t reg(uint32_t offset) {
return *(volatile uint32_t *)(_base + offset);
}
@@ -444,4 +488,4 @@ private:
} // namespace device
-#endif /* _DEVICE_DEVICE_H */ \ No newline at end of file
+#endif /* _DEVICE_DEVICE_H */
diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h
index b4a9cdd53..549879352 100644
--- a/src/drivers/device/i2c.h
+++ b/src/drivers/device/i2c.h
@@ -55,13 +55,11 @@ class __EXPORT I2C : public CDev
public:
- /**
- * Get the address
- */
- uint16_t get_address() {
- return _address;
- }
-
+ /**
+ * Get the address
+ */
+ int16_t get_address() { return _address; }
+
protected:
/**
* The number of times a read or write operation will be retried on
@@ -90,7 +88,7 @@ protected:
uint16_t address,
uint32_t frequency,
int irq = 0);
- ~I2C();
+ virtual ~I2C();
virtual int init();
diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h
new file mode 100644
index 000000000..dc0c84052
--- /dev/null
+++ b/src/drivers/device/ringbuffer.h
@@ -0,0 +1,203 @@
+/****************************************************************************
+ *
+ * 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 ringbuffer.h
+ *
+ * A simple ringbuffer template.
+ */
+
+#pragma once
+
+template<typename T>
+class RingBuffer {
+public:
+ RingBuffer(unsigned size);
+ virtual ~RingBuffer();
+
+ /**
+ * Put an item into the buffer.
+ *
+ * @param val Item to put
+ * @return true if the item was put, false if the buffer is full
+ */
+ bool put(T &val);
+
+ /**
+ * Put an item into the buffer.
+ *
+ * @param val Item to put
+ * @return true if the item was put, false if the buffer is full
+ */
+ bool put(const T &val);
+
+ /**
+ * Get an item from the buffer.
+ *
+ * @param val Item that was gotten
+ * @return true if an item was got, false if the buffer was empty.
+ */
+ bool get(T &val);
+
+ /**
+ * Get an item from the buffer (scalars only).
+ *
+ * @return The value that was fetched, or zero if the buffer was
+ * empty.
+ */
+ T get(void);
+
+ /*
+ * Get the number of slots free in the buffer.
+ *
+ * @return The number of items that can be put into the buffer before
+ * it becomes full.
+ */
+ unsigned space(void);
+
+ /*
+ * Get the number of items in the buffer.
+ *
+ * @return The number of items that can be got from the buffer before
+ * it becomes empty.
+ */
+ unsigned count(void);
+
+ /*
+ * Returns true if the buffer is empty.
+ */
+ bool empty() { return _tail == _head; }
+
+ /*
+ * Returns true if the buffer is full.
+ */
+ bool full() { return _next(_head) == _tail; }
+
+ /*
+ * Returns the capacity of the buffer, or zero if the buffer could
+ * not be allocated.
+ */
+ unsigned size() { return (_buf != nullptr) ? _size : 0; }
+
+ /*
+ * Empties the buffer.
+ */
+ void flush() { _head = _tail = _size; }
+
+private:
+ T *const _buf;
+ const unsigned _size;
+ volatile unsigned _head; /**< insertion point */
+ volatile unsigned _tail; /**< removal point */
+
+ unsigned _next(unsigned index);
+};
+
+template <typename T>
+RingBuffer<T>::RingBuffer(unsigned with_size) :
+ _buf(new T[with_size + 1]),
+ _size(with_size),
+ _head(with_size),
+ _tail(with_size)
+{}
+
+template <typename T>
+RingBuffer<T>::~RingBuffer()
+{
+ if (_buf != nullptr)
+ delete[] _buf;
+}
+
+template <typename T>
+bool RingBuffer<T>::put(T &val)
+{
+ unsigned next = _next(_head);
+ if (next != _tail) {
+ _buf[_head] = val;
+ _head = next;
+ return true;
+ } else {
+ return false;
+ }
+}
+
+template <typename T>
+bool RingBuffer<T>::put(const T &val)
+{
+ unsigned next = _next(_head);
+ if (next != _tail) {
+ _buf[_head] = val;
+ _head = next;
+ return true;
+ } else {
+ return false;
+ }
+}
+
+template <typename T>
+bool RingBuffer<T>::get(T &val)
+{
+ if (_tail != _head) {
+ val = _buf[_tail];
+ _tail = _next(_tail);
+ return true;
+ } else {
+ return false;
+ }
+}
+
+template <typename T>
+T RingBuffer<T>::get(void)
+{
+ T val;
+ return get(val) ? val : 0;
+}
+
+template <typename T>
+unsigned RingBuffer<T>::space(void)
+{
+ return (_tail >= _head) ? (_size - (_tail - _head)) : (_head - _tail - 1);
+}
+
+template <typename T>
+unsigned RingBuffer<T>::count(void)
+{
+ return _size - space();
+}
+
+template <typename T>
+unsigned RingBuffer<T>::_next(unsigned index)
+{
+ return (0 == index) ? _size : (index - 1);
+}
diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h
index d2d01efb3..e0122372a 100644
--- a/src/drivers/device/spi.h
+++ b/src/drivers/device/spi.h
@@ -71,7 +71,7 @@ protected:
enum spi_mode_e mode,
uint32_t frequency,
int irq = 0);
- ~SPI();
+ virtual ~SPI();
virtual int init();
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/drv_pwm_output.h b/src/drivers/drv_pwm_output.h
index 52a667403..ec9d4ca09 100644
--- a/src/drivers/drv_pwm_output.h
+++ b/src/drivers/drv_pwm_output.h
@@ -118,11 +118,8 @@ ORB_DECLARE(output_pwm);
/** start DSM bind */
#define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7)
-/** stop DSM bind */
-#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8)
-
/** Power up DSM receiver */
-#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9)
+#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8)
/** set a single servo to a specific value */
#define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo)
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index b34d3fa5d..cd72d9d23 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()
+ETSAirspeed::ETSAirspeed(int bus, int address) : Airspeed(bus, address,
+ CONVERSION_INTERVAL)
{
- /* 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)
-{
- 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 */
@@ -735,6 +383,10 @@ test()
warnx("diff pressure: %d pa", report.differential_pressure_pa);
}
+ /* reset the sensor polling to its default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
+ errx(1, "failed to set default rate");
+
errx(0, "PASS");
}
@@ -779,11 +431,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/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 98098c83b..1ffca2f43 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -333,8 +333,13 @@ L3GD20::init()
write_reg(ADDR_CTRL_REG4, REG4_BDU);
write_reg(ADDR_CTRL_REG5, 0);
- write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
- write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
+
+ write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
+
+ /* disable FIFO. This makes things simpler and ensures we
+ * aren't getting stale data. It means we must run the hrt
+ * callback fast enough to not miss data. */
+ write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
set_range(500); /* default to 500dps */
set_samplerate(0); /* max sample rate */
diff --git a/src/drivers/md25/BlockSysIdent.cpp b/src/drivers/md25/BlockSysIdent.cpp
new file mode 100644
index 000000000..23b0724d8
--- /dev/null
+++ b/src/drivers/md25/BlockSysIdent.cpp
@@ -0,0 +1,8 @@
+#include "BlockSysIdent.hpp"
+
+BlockSysIdent::BlockSysIdent() :
+ Block(NULL, "SYSID"),
+ _freq(this, "FREQ"),
+ _ampl(this, "AMPL")
+{
+}
diff --git a/src/drivers/md25/BlockSysIdent.hpp b/src/drivers/md25/BlockSysIdent.hpp
new file mode 100644
index 000000000..270635f40
--- /dev/null
+++ b/src/drivers/md25/BlockSysIdent.hpp
@@ -0,0 +1,10 @@
+#include <controllib/block/Block.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+class BlockSysIdent : public control::Block {
+public:
+ BlockSysIdent();
+private:
+ control::BlockParam<float> _freq;
+ control::BlockParam<float> _ampl;
+};
diff --git a/src/drivers/md25/md25.cpp b/src/drivers/md25/md25.cpp
index 71932ad65..d43e3aef9 100644
--- a/src/drivers/md25/md25.cpp
+++ b/src/drivers/md25/md25.cpp
@@ -45,9 +45,16 @@
#include "md25.hpp"
#include <poll.h>
#include <stdio.h>
+#include <math.h>
+#include <string.h>
#include <systemlib/err.h>
#include <arch/board/board.h>
+#include <mavlink/mavlink_log.h>
+
+#include <controllib/uorb/UOrbPublication.hpp>
+#include <uORB/topics/debug_key_value.h>
+#include <drivers/drv_hrt.h>
// registers
enum {
@@ -72,6 +79,9 @@ enum {
REG_COMMAND_RW,
};
+// File descriptors
+static int mavlink_fd;
+
MD25::MD25(const char *deviceName, int bus,
uint16_t address, uint32_t speed) :
I2C("MD25", deviceName, bus, address, speed),
@@ -106,7 +116,8 @@ MD25::MD25(const char *deviceName, int bus,
setMotor2Speed(0);
resetEncoders();
_setMode(MD25::MODE_UNSIGNED_SPEED);
- setSpeedRegulation(true);
+ setSpeedRegulation(false);
+ setMotorAccel(10);
setTimeout(true);
}
@@ -298,6 +309,12 @@ int MD25::setDeviceAddress(uint8_t address)
return OK;
}
+int MD25::setMotorAccel(uint8_t accel)
+{
+ return _writeUint8(REG_ACCEL_RATE_RW,
+ accel);
+}
+
int MD25::setMotor1Speed(float value)
{
return _writeUint8(REG_SPEED1_RW,
@@ -451,12 +468,12 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
MD25 md25("/dev/md25", bus, address);
// print status
- char buf[200];
+ char buf[400];
md25.status(buf, sizeof(buf));
printf("%s\n", buf);
// setup for test
- md25.setSpeedRegulation(true);
+ md25.setSpeedRegulation(false);
md25.setTimeout(true);
float dt = 0.1;
float speed = 0.2;
@@ -550,4 +567,68 @@ int md25Test(const char *deviceName, uint8_t bus, uint8_t address)
return 0;
}
+int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency)
+{
+ printf("md25 sine: starting\n");
+
+ // setup
+ MD25 md25("/dev/md25", bus, address);
+
+ // print status
+ char buf[400];
+ md25.status(buf, sizeof(buf));
+ printf("%s\n", buf);
+
+ // setup for test
+ md25.setSpeedRegulation(false);
+ md25.setTimeout(true);
+ float dt = 0.01;
+ float t_final = 60.0;
+ float prev_revolution = md25.getRevolutions1();
+
+ // debug publication
+ control::UOrbPublication<debug_key_value_s> debug_msg(NULL,
+ ORB_ID(debug_key_value));
+
+ // sine wave for motor 1
+ md25.resetEncoders();
+ while (true) {
+
+ // input
+ uint64_t timestamp = hrt_absolute_time();
+ float t = timestamp/1000000.0f;
+
+ float input_value = amplitude*sinf(2*M_PI*frequency*t);
+ md25.setMotor1Speed(input_value);
+
+ // output
+ md25.readData();
+ float current_revolution = md25.getRevolutions1();
+
+ // send input message
+ //strncpy(debug_msg.key, "md25 in ", 10);
+ //debug_msg.timestamp_ms = 1000*timestamp;
+ //debug_msg.value = input_value;
+ //debug_msg.update();
+
+ // send output message
+ strncpy(debug_msg.key, "md25 out ", 10);
+ debug_msg.timestamp_ms = 1000*timestamp;
+ debug_msg.value = current_revolution;
+ debug_msg.update();
+
+ if (t > t_final) break;
+
+ // update for next step
+ prev_revolution = current_revolution;
+
+ // sleep
+ usleep(1000000 * dt);
+ }
+ md25.setMotor1Speed(0);
+
+ printf("md25 sine complete\n");
+ return 0;
+}
+
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/md25/md25.hpp b/src/drivers/md25/md25.hpp
index e77511b16..1661f67f9 100644
--- a/src/drivers/md25/md25.hpp
+++ b/src/drivers/md25/md25.hpp
@@ -46,7 +46,7 @@
#include <poll.h>
#include <stdio.h>
-#include <controllib/block/UOrbSubscription.hpp>
+#include <controllib/uorb/UOrbSubscription.hpp>
#include <uORB/topics/actuator_controls.h>
#include <drivers/device/i2c.h>
@@ -213,6 +213,19 @@ public:
int setDeviceAddress(uint8_t address);
/**
+ * set motor acceleration
+ * @param accel
+ * controls motor speed change (1-10)
+ * accel rate | time for full fwd. to full rev.
+ * 1 | 6.375 s
+ * 2 | 1.6 s
+ * 3 | 0.675 s
+ * 5(default) | 1.275 s
+ * 10 | 0.65 s
+ */
+ int setMotorAccel(uint8_t accel);
+
+ /**
* set motor 1 speed
* @param normSpeed normalize speed between -1 and 1
* @return non-zero -> error
@@ -290,4 +303,7 @@ private:
// unit testing
int md25Test(const char *deviceName, uint8_t bus, uint8_t address);
+// sine testing
+int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitude, float frequency);
+
// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78
diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp
index e62c46b0d..7e5904d05 100644
--- a/src/drivers/md25/md25_main.cpp
+++ b/src/drivers/md25/md25_main.cpp
@@ -82,7 +82,7 @@ usage(const char *reason)
if (reason)
fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n");
+ fprintf(stderr, "usage: md25 {start|stop|read|status|search|test|change_address}\n\n");
exit(1);
}
@@ -136,6 +136,28 @@ int md25_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "sine")) {
+
+ if (argc < 6) {
+ printf("usage: md25 sine bus address amp freq\n");
+ exit(0);
+ }
+
+ const char *deviceName = "/dev/md25";
+
+ uint8_t bus = strtoul(argv[2], nullptr, 0);
+
+ uint8_t address = strtoul(argv[3], nullptr, 0);
+
+ float amplitude = atof(argv[4]);
+
+ float frequency = atof(argv[5]);
+
+ md25Sine(deviceName, bus, address, amplitude, frequency);
+
+ exit(0);
+ }
+
if (!strcmp(argv[1], "probe")) {
if (argc < 4) {
printf("usage: md25 probe bus address\n");
@@ -162,6 +184,29 @@ int md25_main(int argc, char *argv[])
exit(0);
}
+ if (!strcmp(argv[1], "read")) {
+ if (argc < 4) {
+ printf("usage: md25 read bus address\n");
+ exit(0);
+ }
+
+ const char *deviceName = "/dev/md25";
+
+ uint8_t bus = strtoul(argv[2], nullptr, 0);
+
+ uint8_t address = strtoul(argv[3], nullptr, 0);
+
+ MD25 md25(deviceName, bus, address);
+
+ // print status
+ char buf[400];
+ md25.status(buf, sizeof(buf));
+ printf("%s\n", buf);
+
+ exit(0);
+ }
+
+
if (!strcmp(argv[1], "search")) {
if (argc < 3) {
printf("usage: md25 search bus\n");
@@ -246,7 +291,7 @@ int md25_thread_main(int argc, char *argv[])
uint8_t address = strtoul(argv[4], nullptr, 0);
// start
- MD25 md25("/dev/md25", bus, address);
+ MD25 md25(deviceName, bus, address);
thread_running = true;
diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp
new file mode 100644
index 000000000..68d2c5d65
--- /dev/null
+++ b/src/drivers/meas_airspeed/meas_airspeed.cpp
@@ -0,0 +1,520 @@
+/****************************************************************************
+ *
+ * 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 Sarthak Kaingade
+ * @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 */
+
+/* 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], 4);
+
+ 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];
+
+ // XXX leaving this in until new calculation method has been cross-checked
+ //diff_pres_pa = abs(diff_pres_pa - (16384 / 2.0f));
+ //diff_pres_pa -= _diff_pres_offset;
+ int16_t dp_raw = 0, dT_raw = 0;
+ dp_raw = (val[0] << 8) + val[1];
+ dp_raw = 0x3FFF & dp_raw;
+ dT_raw = (val[2] << 8) + val[3];
+ dT_raw = (0xFFE0 & dT_raw) >> 5;
+ float temperature = ((200 * dT_raw) / 2047) - 50;
+
+ // XXX we may want to smooth out the readings to remove noise.
+
+ // Calculate differential pressure. As its centered around 8000
+ // and can go positive or negative, enforce absolute value
+ uint16_t diff_press_pa = abs(dp_raw - (16384 / 2.0f));
+
+ _reports[_next_report].timestamp = hrt_absolute_time();
+ _reports[_next_report].temperature = temperature;
+ _reports[_next_report].differential_pressure_pa = diff_press_pa;
+
+ // Track maximum differential pressure measured (so we can work out top speed).
+ if (diff_press_pa > _reports[_next_report].max_differential_pressure_pa) {
+ _reports[_next_report].max_differential_pressure_pa = diff_press_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);
+ }
+
+ /* reset the sensor polling to its default rate */
+ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT))
+ errx(1, "failed to set default rate");
+
+ 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..c4e331a30 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>
@@ -64,8 +67,10 @@
#include <drivers/drv_hrt.h>
#include <drivers/device/spi.h>
+#include <drivers/device/ringbuffer.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
#define DIR_READ 0x80
#define DIR_WRITE 0x00
@@ -178,21 +183,33 @@ private:
struct hrt_call _call;
unsigned _call_interval;
- struct accel_report _accel_report;
+ typedef RingBuffer<accel_report> AccelReportBuffer;
+ AccelReportBuffer *_accel_reports;
+
struct accel_scale _accel_scale;
float _accel_range_scale;
float _accel_range_m_s2;
orb_advert_t _accel_topic;
- struct gyro_report _gyro_report;
+ typedef RingBuffer<gyro_report> GyroReportBuffer;
+ GyroReportBuffer *_gyro_reports;
+
struct gyro_scale _gyro_scale;
float _gyro_range_scale;
float _gyro_range_rad_s;
orb_advert_t _gyro_topic;
unsigned _reads;
+ unsigned _sample_rate;
perf_counter_t _sample_perf;
+ math::LowPassFilter2p _accel_filter_x;
+ math::LowPassFilter2p _accel_filter_y;
+ math::LowPassFilter2p _accel_filter_z;
+ math::LowPassFilter2p _gyro_filter_x;
+ math::LowPassFilter2p _gyro_filter_y;
+ math::LowPassFilter2p _gyro_filter_z;
+
/**
* Start automatic measurement.
*/
@@ -204,6 +221,13 @@ private:
void stop();
/**
+ * Reset chip.
+ *
+ * Resets the chip and measurements ranges, but not scale and offset.
+ */
+ void reset();
+
+ /**
* Static trampoline from the hrt_call context; because we don't have a
* generic hrt wrapper yet.
*
@@ -215,7 +239,7 @@ private:
static void measure_trampoline(void *arg);
/**
- * Fetch measurements from the sensor and update the report ring.
+ * Fetch measurements from the sensor and update the report buffers.
*/
void measure();
@@ -307,14 +331,23 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro(new MPU6000_gyro(this)),
_product(0),
_call_interval(0),
+ _accel_reports(nullptr),
_accel_range_scale(0.0f),
_accel_range_m_s2(0.0f),
_accel_topic(-1),
+ _gyro_reports(nullptr),
_gyro_range_scale(0.0f),
_gyro_range_rad_s(0.0f),
_gyro_topic(-1),
_reads(0),
- _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read"))
+ _sample_rate(1000),
+ _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")),
+ _accel_filter_x(1000, 30),
+ _accel_filter_y(1000, 30),
+ _accel_filter_z(1000, 30),
+ _gyro_filter_x(1000, 30),
+ _gyro_filter_y(1000, 30),
+ _gyro_filter_z(1000, 30)
{
// disable debug() calls
_debug_enabled = false;
@@ -335,8 +368,6 @@ MPU6000::MPU6000(int bus, spi_dev_e device) :
_gyro_scale.z_offset = 0;
_gyro_scale.z_scale = 1.0f;
- memset(&_accel_report, 0, sizeof(_accel_report));
- memset(&_gyro_report, 0, sizeof(_gyro_report));
memset(&_call, 0, sizeof(_call));
}
@@ -348,6 +379,12 @@ MPU6000::~MPU6000()
/* delete the gyro subdriver */
delete _gyro;
+ /* free any existing reports */
+ if (_accel_reports != nullptr)
+ delete _accel_reports;
+ if (_gyro_reports != nullptr)
+ delete _gyro_reports;
+
/* delete the perf counter */
perf_free(_sample_perf);
}
@@ -356,6 +393,7 @@ int
MPU6000::init()
{
int ret;
+ int gyro_ret;
/* do SPI init (and probe) first */
ret = SPI::init();
@@ -366,9 +404,58 @@ 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);
+ /* allocate basic report buffers */
+ _accel_reports = new AccelReportBuffer(2);
+ if (_accel_reports == nullptr)
+ goto out;
+
+ _gyro_reports = new GyroReportBuffer(2);
+ if (_gyro_reports == nullptr)
+ goto out;
+
+ reset();
+
+ /* Initialize offsets and scales */
+ _accel_scale.x_offset = 0;
+ _accel_scale.x_scale = 1.0f;
+ _accel_scale.y_offset = 0;
+ _accel_scale.y_scale = 1.0f;
+ _accel_scale.z_offset = 0;
+ _accel_scale.z_scale = 1.0f;
+
+ _gyro_scale.x_offset = 0;
+ _gyro_scale.x_scale = 1.0f;
+ _gyro_scale.y_offset = 0;
+ _gyro_scale.y_scale = 1.0f;
+ _gyro_scale.z_offset = 0;
+ _gyro_scale.z_scale = 1.0f;
+
+ /* do CDev init for the gyro device node, keep it optional */
+ gyro_ret = _gyro->init();
+
+ /* fetch an initial set of measurements for advertisement */
+ measure();
+
+ if (gyro_ret != OK) {
+ _gyro_topic = -1;
+ } else {
+ gyro_report gr;
+ _gyro_reports->get(gr);
+
+ _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr);
+ }
+
+ /* advertise accel topic */
+ accel_report ar;
+ _accel_reports->get(ar);
+ _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar);
+
+out:
+ return ret;
+}
+
+void MPU6000::reset()
+{
// Chip reset
write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
@@ -384,13 +471,13 @@ 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)
// was 90 Hz, but this ruins quality and does not improve the
// system response
- _set_dlpf_filter(20);
+ _set_dlpf_filter(42);
usleep(1000);
// Gyro scale 2000 deg/s ()
write_reg(MPUREG_GYRO_CONFIG, BITS_FS_2000DPS);
@@ -401,12 +488,6 @@ MPU6000::init()
// 2000 deg/s = (2000/180)*PI = 34.906585 rad/s
// scaling factor:
// 1/(2^15)*(2000/180)*PI
- _gyro_scale.x_offset = 0;
- _gyro_scale.x_scale = 1.0f;
- _gyro_scale.y_offset = 0;
- _gyro_scale.y_scale = 1.0f;
- _gyro_scale.z_offset = 0;
- _gyro_scale.z_scale = 1.0f;
_gyro_range_scale = (0.0174532 / 16.4);//1.0f / (32768.0f * (2000.0f / 180.0f) * M_PI_F);
_gyro_range_rad_s = (2000.0f / 180.0f) * M_PI_F;
@@ -439,12 +520,6 @@ MPU6000::init()
// Correct accel scale factors of 4096 LSB/g
// scale to m/s^2 ( 1g = 9.81 m/s^2)
- _accel_scale.x_offset = 0;
- _accel_scale.x_scale = 1.0f;
- _accel_scale.y_offset = 0;
- _accel_scale.y_scale = 1.0f;
- _accel_scale.z_offset = 0;
- _accel_scale.z_scale = 1.0f;
_accel_range_scale = (9.81f / 4096.0f);
_accel_range_m_s2 = 8.0f * 9.81f;
@@ -460,14 +535,6 @@ MPU6000::init()
// write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
usleep(1000);
- /* do CDev init for the gyro device node, keep it optional */
- int gyro_ret = _gyro->init();
-
- if (gyro_ret != OK) {
- _gyro_topic = -1;
- }
-
- return ret;
}
int
@@ -509,6 +576,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;
}
/*
@@ -545,21 +613,33 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz)
ssize_t
MPU6000::read(struct file *filp, char *buffer, size_t buflen)
{
- int ret = 0;
+ unsigned count = buflen / sizeof(accel_report);
/* buffer must be large enough */
- if (buflen < sizeof(_accel_report))
+ if (count < 1)
return -ENOSPC;
- /* if automatic measurement is not enabled */
- if (_call_interval == 0)
+ /* if automatic measurement is not enabled, get a fresh measurement into the buffer */
+ if (_call_interval == 0) {
+ _accel_reports->flush();
measure();
+ }
- /* copy out the latest reports */
- memcpy(buffer, &_accel_report, sizeof(_accel_report));
- ret = sizeof(_accel_report);
+ /* if no data, error (we could block here) */
+ if (_accel_reports->empty())
+ return -EAGAIN;
+
+ /* copy reports out of our buffer to the caller */
+ accel_report *arp = reinterpret_cast<accel_report *>(buffer);
+ int transferred = 0;
+ while (count--) {
+ if (!_accel_reports->get(*arp++))
+ break;
+ transferred++;
+ }
- return ret;
+ /* return the number of bytes transferred */
+ return (transferred * sizeof(accel_report));
}
int
@@ -576,21 +656,33 @@ MPU6000::self_test()
ssize_t
MPU6000::gyro_read(struct file *filp, char *buffer, size_t buflen)
{
- int ret = 0;
+ unsigned count = buflen / sizeof(gyro_report);
/* buffer must be large enough */
- if (buflen < sizeof(_gyro_report))
+ if (count < 1)
return -ENOSPC;
- /* if automatic measurement is not enabled */
- if (_call_interval == 0)
+ /* if automatic measurement is not enabled, get a fresh measurement into the buffer */
+ if (_call_interval == 0) {
+ _gyro_reports->flush();
measure();
+ }
- /* copy out the latest report */
- memcpy(buffer, &_gyro_report, sizeof(_gyro_report));
- ret = sizeof(_gyro_report);
+ /* if no data, error (we could block here) */
+ if (_gyro_reports->empty())
+ return -EAGAIN;
+
+ /* copy reports out of our buffer to the caller */
+ gyro_report *arp = reinterpret_cast<gyro_report *>(buffer);
+ int transferred = 0;
+ while (count--) {
+ if (!_gyro_reports->get(*arp++))
+ break;
+ transferred++;
+ }
- return ret;
+ /* return the number of bytes transferred */
+ return (transferred * sizeof(gyro_report));
}
int
@@ -598,6 +690,10 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
{
switch (cmd) {
+ case SENSORIOCRESET:
+ reset();
+ return OK;
+
case SENSORIOCSPOLLRATE: {
switch (arg) {
@@ -617,8 +713,8 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
- /* XXX 500Hz is just a wild guess */
- return ioctl(filp, SENSORIOCSPOLLRATE, 500);
+ /* set to same as sample rate per default */
+ return ioctl(filp, SENSORIOCSPOLLRATE, _sample_rate);
/* adjust to a legal polling interval in Hz */
default: {
@@ -632,6 +728,19 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
if (ticks < 1000)
return -EINVAL;
+ // adjust filters
+ float cutoff_freq_hz = _accel_filter_x.get_cutoff_freq();
+ float sample_rate = 1.0e6f/ticks;
+ _accel_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+ _accel_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+ _accel_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz);
+
+
+ float cutoff_freq_hz_gyro = _gyro_filter_x.get_cutoff_freq();
+ _gyro_filter_x.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+ _gyro_filter_y.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+ _gyro_filter_z.set_cutoff_frequency(sample_rate, cutoff_freq_hz_gyro);
+
/* update interval for next measurement */
/* XXX this is a bit shady, but no other way to adjust... */
_call.period = _call_interval = ticks;
@@ -651,23 +760,51 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg)
return 1000000 / _call_interval;
- case SENSORIOCSQUEUEDEPTH:
- /* XXX not implemented */
- return -EINVAL;
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ AccelReportBuffer *buf = new AccelReportBuffer(arg);
+
+ if (nullptr == buf)
+ return -ENOMEM;
+ if (buf->size() == 0) {
+ delete buf;
+ return -ENOMEM;
+ }
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete _accel_reports;
+ _accel_reports = buf;
+ start();
+
+ return OK;
+ }
case SENSORIOCGQUEUEDEPTH:
- /* XXX not implemented */
- return -EINVAL;
+ return _accel_reports->size();
+ case ACCELIOCGSAMPLERATE:
+ return _sample_rate;
case ACCELIOCSSAMPLERATE:
- case ACCELIOCGSAMPLERATE:
- _set_sample_rate(arg);
- return OK;
+ _set_sample_rate(arg);
+ return OK;
- case ACCELIOCSLOWPASS:
case ACCELIOCGLOWPASS:
- _set_dlpf_filter((uint16_t)arg);
+ return _accel_filter_x.get_cutoff_freq();
+
+ case ACCELIOCSLOWPASS:
+
+ // XXX decide on relationship of both filters
+ // i.e. disable the on-chip filter
+ //_set_dlpf_filter((uint16_t)arg);
+ _accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
return OK;
case ACCELIOCSSCALE:
@@ -689,12 +826,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();
@@ -713,19 +851,51 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg)
/* these are shared with the accel side */
case SENSORIOCSPOLLRATE:
case SENSORIOCGPOLLRATE:
- case SENSORIOCSQUEUEDEPTH:
- case SENSORIOCGQUEUEDEPTH:
case SENSORIOCRESET:
return ioctl(filp, cmd, arg);
- case GYROIOCSSAMPLERATE:
+ case SENSORIOCSQUEUEDEPTH: {
+ /* lower bound is mandatory, upper bound is a sanity check */
+ if ((arg < 1) || (arg > 100))
+ return -EINVAL;
+
+ /* allocate new buffer */
+ GyroReportBuffer *buf = new GyroReportBuffer(arg);
+
+ if (nullptr == buf)
+ return -ENOMEM;
+ if (buf->size() == 0) {
+ delete buf;
+ return -ENOMEM;
+ }
+
+ /* reset the measurement state machine with the new buffer, free the old */
+ stop();
+ delete _gyro_reports;
+ _gyro_reports = buf;
+ start();
+
+ return OK;
+ }
+
+ case SENSORIOCGQUEUEDEPTH:
+ return _gyro_reports->size();
+
case GYROIOCGSAMPLERATE:
- _set_sample_rate(arg);
- return OK;
+ return _sample_rate;
+
+ case GYROIOCSSAMPLERATE:
+ _set_sample_rate(arg);
+ return OK;
- case GYROIOCSLOWPASS:
case GYROIOCGLOWPASS:
- _set_dlpf_filter((uint16_t)arg);
+ return _gyro_filter_x.get_cutoff_freq();
+ case GYROIOCSLOWPASS:
+ _gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ _gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg);
+ // XXX check relation to the internal lowpass
+ //_set_dlpf_filter((uint16_t)arg);
return OK;
case GYROIOCSSCALE:
@@ -739,12 +909,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();
@@ -849,6 +1020,10 @@ MPU6000::start()
/* make sure we are stopped first */
stop();
+ /* discard any stale data in the buffers */
+ _accel_reports->flush();
+ _gyro_reports->flush();
+
/* start polling at the specified rate */
hrt_call_every(&_call, 1000, _call_interval, (hrt_callout)&MPU6000::measure_trampoline, this);
}
@@ -862,7 +1037,7 @@ MPU6000::stop()
void
MPU6000::measure_trampoline(void *arg)
{
- MPU6000 *dev = (MPU6000 *)arg;
+ MPU6000 *dev = reinterpret_cast<MPU6000 *>(arg);
/* make another measurement */
dev->measure();
@@ -944,9 +1119,15 @@ MPU6000::measure()
report.gyro_y = gyro_yt;
/*
+ * Report buffers.
+ */
+ accel_report arb;
+ gyro_report grb;
+
+ /*
* Adjust and scale results to m/s^2.
*/
- _gyro_report.timestamp = _accel_report.timestamp = hrt_absolute_time();
+ grb.timestamp = arb.timestamp = hrt_absolute_time();
/*
@@ -967,40 +1148,53 @@ MPU6000::measure()
/* NOTE: Axes have been swapped to match the board a few lines above. */
- _accel_report.x_raw = report.accel_x;
- _accel_report.y_raw = report.accel_y;
- _accel_report.z_raw = report.accel_z;
+ arb.x_raw = report.accel_x;
+ arb.y_raw = report.accel_y;
+ arb.z_raw = report.accel_z;
- _accel_report.x = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
- _accel_report.y = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
- _accel_report.z = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
- _accel_report.scaling = _accel_range_scale;
- _accel_report.range_m_s2 = _accel_range_m_s2;
+ float x_in_new = ((report.accel_x * _accel_range_scale) - _accel_scale.x_offset) * _accel_scale.x_scale;
+ float y_in_new = ((report.accel_y * _accel_range_scale) - _accel_scale.y_offset) * _accel_scale.y_scale;
+ float z_in_new = ((report.accel_z * _accel_range_scale) - _accel_scale.z_offset) * _accel_scale.z_scale;
+
+ arb.x = _accel_filter_x.apply(x_in_new);
+ arb.y = _accel_filter_y.apply(y_in_new);
+ arb.z = _accel_filter_z.apply(z_in_new);
- _accel_report.temperature_raw = report.temp;
- _accel_report.temperature = (report.temp) / 361.0f + 35.0f;
+ arb.scaling = _accel_range_scale;
+ arb.range_m_s2 = _accel_range_m_s2;
- _gyro_report.x_raw = report.gyro_x;
- _gyro_report.y_raw = report.gyro_y;
- _gyro_report.z_raw = report.gyro_z;
+ arb.temperature_raw = report.temp;
+ arb.temperature = (report.temp) / 361.0f + 35.0f;
- _gyro_report.x = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
- _gyro_report.y = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
- _gyro_report.z = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
- _gyro_report.scaling = _gyro_range_scale;
- _gyro_report.range_rad_s = _gyro_range_rad_s;
+ grb.x_raw = report.gyro_x;
+ grb.y_raw = report.gyro_y;
+ grb.z_raw = report.gyro_z;
- _gyro_report.temperature_raw = report.temp;
- _gyro_report.temperature = (report.temp) / 361.0f + 35.0f;
+ float x_gyro_in_new = ((report.gyro_x * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
+ float y_gyro_in_new = ((report.gyro_y * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale;
+ float z_gyro_in_new = ((report.gyro_z * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale;
+
+ grb.x = _gyro_filter_x.apply(x_gyro_in_new);
+ grb.y = _gyro_filter_y.apply(y_gyro_in_new);
+ grb.z = _gyro_filter_z.apply(z_gyro_in_new);
+
+ grb.scaling = _gyro_range_scale;
+ grb.range_rad_s = _gyro_range_rad_s;
+
+ grb.temperature_raw = report.temp;
+ grb.temperature = (report.temp) / 361.0f + 35.0f;
+
+ _accel_reports->put(arb);
+ _gyro_reports->put(grb);
/* notify anyone waiting for data */
poll_notify(POLLIN);
_gyro->parent_poll_notify();
/* and publish for subscribers */
- orb_publish(ORB_ID(sensor_accel), _accel_topic, &_accel_report);
+ orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb);
if (_gyro_topic != -1) {
- orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &_gyro_report);
+ orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &grb);
}
/* stop measuring */
@@ -1103,21 +1297,19 @@ fail:
void
test()
{
- int fd = -1;
- int fd_gyro = -1;
- struct accel_report a_report;
- struct gyro_report g_report;
+ accel_report a_report;
+ gyro_report g_report;
ssize_t sz;
/* get the driver */
- fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
if (fd < 0)
err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)",
ACCEL_DEVICE_PATH);
/* get the driver */
- fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
+ int fd_gyro = open(GYRO_DEVICE_PATH, O_RDONLY);
if (fd_gyro < 0)
err(1, "%s open failed", GYRO_DEVICE_PATH);
@@ -1129,8 +1321,10 @@ test()
/* do a simple demand read */
sz = read(fd, &a_report, sizeof(a_report));
- if (sz != sizeof(a_report))
+ if (sz != sizeof(a_report)) {
+ warnx("ret: %d, expected: %d", sz, sizeof(a_report));
err(1, "immediate acc read failed");
+ }
warnx("single read");
warnx("time: %lld", a_report.timestamp);
@@ -1146,8 +1340,10 @@ test()
/* do a simple demand read */
sz = read(fd_gyro, &g_report, sizeof(g_report));
- if (sz != sizeof(g_report))
+ if (sz != sizeof(g_report)) {
+ warnx("ret: %d, expected: %d", sz, sizeof(g_report));
err(1, "immediate gyro read failed");
+ }
warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x);
warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y);
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index bc3f1dcc6..2953639bf 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -207,6 +207,12 @@ private:
bool _dsm_vcc_ctl;
/**
+ * System armed
+ */
+
+ bool _system_armed;
+
+ /**
* Trampoline to the worker task
*/
static void task_main_trampoline(int argc, char *argv[]);
@@ -374,7 +380,8 @@ PX4IO::PX4IO() :
_battery_amp_bias(0),
_battery_mamphour_total(0),
_battery_last_timestamp(0),
- _dsm_vcc_ctl(false)
+ _dsm_vcc_ctl(false),
+ _system_armed(false)
{
/* we need this potentially before it could be set in task_main */
g_dev = this;
@@ -633,9 +640,11 @@ void
PX4IO::task_main()
{
hrt_abstime last_poll_time = 0;
+ int mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0);
log("starting");
+
/*
* Subscribe to the appropriate PWM output topic based on whether we are the
* primary PWM output or not.
@@ -735,6 +744,25 @@ PX4IO::task_main()
*/
if (fds[3].revents & POLLIN) {
parameter_update_s pupdate;
+ int32_t dsm_bind_val;
+ param_t dsm_bind_param;
+
+ // See if bind parameter has been set, and reset it to 0
+ param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val);
+ if (dsm_bind_val) {
+ if (!_system_armed) {
+ if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) {
+ mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x');
+ ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7);
+ } else {
+ mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected");
+ }
+ } else {
+ mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected");
+ }
+ dsm_bind_val = 0;
+ param_set(dsm_bind_param, &dsm_bind_val);
+ }
/* copy to reset the notification */
orb_copy(ORB_ID(parameter_update), _t_param, &pupdate);
@@ -842,6 +870,8 @@ PX4IO::io_set_arming_state()
uint16_t set = 0;
uint16_t clear = 0;
+ _system_armed = vstatus.flag_system_armed;
+
if (armed.armed && !armed.lockdown) {
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
} else {
@@ -1578,16 +1608,11 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg)
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
usleep(500000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out);
- usleep(1000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up);
- usleep(100000);
+ usleep(50000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4));
- break;
-
- case DSM_BIND_STOP:
- io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down);
+ usleep(50000);
io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart);
- usleep(500000);
break;
case DSM_BIND_POWER_UP:
@@ -1829,30 +1854,12 @@ bind(int argc, char *argv[])
else
errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]);
- /* Open console directly to grab CTRL-C signal */
- int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY);
- if (!console)
- errx(1, "failed opening console");
-
warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1.");
- warnx("Press CTRL-C or 'c' when done.");
g_dev->ioctl(nullptr, DSM_BIND_START, pulses);
- for (;;) {
- usleep(500000L);
- /* Check if user wants to quit */
- char c;
- if (read(console, &c, 1) == 1) {
- if (c == 0x03 || c == 0x63) {
- warnx("Done\n");
- g_dev->ioctl(nullptr, DSM_BIND_STOP, 0);
- g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0);
- close(console);
- exit(0);
- }
- }
- }
+ exit(0);
+
}
void
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index 7ef3db970..83a1a1abb 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -70,7 +70,7 @@
#include "stm32_gpio.h"
#include "stm32_tim.h"
-#ifdef CONFIG_HRT_TIMER
+#ifdef HRT_TIMER
/* HRT configuration */
#if HRT_TIMER == 1
@@ -155,7 +155,7 @@
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
#else
-# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
+# error HRT_TIMER must be a value between 1 and 11
#endif
/*
@@ -275,7 +275,7 @@ static void hrt_call_invoke(void);
/*
* Specific registers and bits used by PPM sub-functions
*/
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/*
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
*
@@ -326,7 +326,7 @@ static void hrt_call_invoke(void);
# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
# define CCER_PPM_FLIP GTIM_CCER_CC4P
# else
-# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
+# error HRT_PPM_CHANNEL must be a value between 1 and 4
# endif
/*
@@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status);
# define CCMR1_PPM 0
# define CCMR2_PPM 0
# define CCER_PPM 0
-#endif /* CONFIG_HRT_PPM */
+#endif /* HRT_PPM_CHANNEL */
/*
* Initialise the timer we are going to use.
@@ -424,7 +424,7 @@ hrt_tim_init(void)
up_enable_irq(HRT_TIMER_VECTOR);
}
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/*
* Handle the PPM decoder state machine.
*/
@@ -526,7 +526,7 @@ error:
ppm_decoded_channels = 0;
}
-#endif /* CONFIG_HRT_PPM */
+#endif /* HRT_PPM_CHANNEL */
/*
* Handle the compare interupt by calling the callout dispatcher
@@ -546,7 +546,7 @@ hrt_tim_isr(int irq, void *context)
/* ack the interrupts we just read */
rSR = ~status;
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/* was this a PPM edge? */
if (status & (SR_INT_PPM | SR_OVF_PPM)) {
@@ -686,7 +686,7 @@ hrt_init(void)
sq_init(&callout_queue);
hrt_tim_init();
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
/* configure the PPM input pin */
stm32_configgpio(GPIO_PPM_IN);
#endif
@@ -907,4 +907,4 @@ hrt_latency_update(void)
}
-#endif /* CONFIG_HRT_TIMER */
+#endif /* HRT_TIMER */
diff --git a/src/drivers/stm32/drv_pwm_servo.c b/src/drivers/stm32/drv_pwm_servo.c
index 7b060412c..dbb45a138 100644
--- a/src/drivers/stm32/drv_pwm_servo.c
+++ b/src/drivers/stm32/drv_pwm_servo.c
@@ -88,6 +88,7 @@
#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
+#define rBDTR(_tmr) REG(_tmr, STM32_ATIM_BDTR_OFFSET)
static void pwm_timer_init(unsigned timer);
static void pwm_timer_set_rate(unsigned timer, unsigned rate);
@@ -110,6 +111,11 @@ pwm_timer_init(unsigned timer)
rCCER(timer) = 0;
rDCR(timer) = 0;
+ if ((pwm_timers[timer].base == STM32_TIM1_BASE) || (pwm_timers[timer].base == STM32_TIM8_BASE)) {
+ /* master output enable = on */
+ rBDTR(timer) = ATIM_BDTR_MOE;
+ }
+
/* configure the timer to free-run at 1MHz */
rPSC(timer) = (pwm_timers[timer].clock_freq / 1000000) - 1;
diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
index e1409a815..b36ba306b 100644
--- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp
+++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp
@@ -117,10 +117,6 @@
#include <systemlib/err.h>
-#ifndef CONFIG_HRT_TIMER
-# error This driver requires CONFIG_HRT_TIMER
-#endif
-
/* Tone alarm configuration */
#if TONE_ALARM_TIMER == 2
# define TONE_ALARM_BASE STM32_TIM2_BASE
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
index 49d0d157d..f01ee0355 100644
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
+++ b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
@@ -47,8 +47,8 @@
#include <mathlib/mathlib.h>
#include <controllib/blocks.hpp>
#include <controllib/block/BlockParam.hpp>
-#include <controllib/block/UOrbSubscription.hpp>
-#include <controllib/block/UOrbPublication.hpp>
+#include <controllib/uorb/UOrbSubscription.hpp>
+#include <controllib/uorb/UOrbPublication.hpp>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_global_position.h>
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index 19c96e9f4..65abcde1e 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -224,8 +224,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* subscribe to raw data */
int sub_raw = orb_subscribe(ORB_ID(sensor_combined));
- /* rate-limit raw data updates to 200Hz */
- orb_set_interval(sub_raw, 4);
+ /* rate-limit raw data updates to 333 Hz (sensors app publishes at 200, so this is just paranoid) */
+ orb_set_interval(sub_raw, 3);
/* subscribe to param changes */
int sub_params = orb_subscribe(ORB_ID(parameter_update));
@@ -236,7 +236,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* advertise attitude */
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
-
int loopcounter = 0;
int printcounter = 0;
@@ -384,7 +383,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
static bool const_initialized = false;
/* initialize with good values once we have a reasonable dt estimate */
- if (!const_initialized && dt < 0.05f && dt > 0.005f) {
+ if (!const_initialized && dt < 0.05f && dt > 0.001f) {
dt = 0.005f;
parameters_update(&ekf_param_handles, &ekf_params);
@@ -424,7 +423,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- if (last_data > 0 && raw.timestamp - last_data > 12000) printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
+ if (last_data > 0 && raw.timestamp - last_data > 12000)
+ printf("[attitude estimator ekf] sensor data missed! (%llu)\n", raw.timestamp - last_data);
last_data = raw.timestamp;
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index df92d51d2..b3a5d012b 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -275,8 +275,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.cpp b/src/modules/commander/commander.cpp
index c6e209f0f..204a41450 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1317,6 +1317,7 @@ toggle_status_leds(vehicle_status_s *status, actuator_armed_s *armed, vehicle_gp
/* ready to arm, blink at 2.5Hz */
if (leds_counter & 8) {
led_on(LED_AMBER);
+
} else {
led_off(LED_AMBER);
}
@@ -1552,6 +1553,7 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "[cmd] parameters load ERROR");
tune_error();
}
+
low_prio_task = LOW_PRIO_TASK_NONE;
break;
@@ -1564,6 +1566,7 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "[cmd] parameters save error");
tune_error();
}
+
low_prio_task = LOW_PRIO_TASK_NONE;
break;
diff --git a/src/modules/controllib/block/Block.cpp b/src/modules/controllib/block/Block.cpp
index 5994d2315..b964d40a3 100644
--- a/src/modules/controllib/block/Block.cpp
+++ b/src/modules/controllib/block/Block.cpp
@@ -43,8 +43,8 @@
#include "Block.hpp"
#include "BlockParam.hpp"
-#include "UOrbSubscription.hpp"
-#include "UOrbPublication.hpp"
+#include "../uorb/UOrbSubscription.hpp"
+#include "../uorb/UOrbPublication.hpp"
namespace control
{
diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp
index 7a785d12e..fefe99702 100644
--- a/src/modules/controllib/blocks.hpp
+++ b/src/modules/controllib/blocks.hpp
@@ -42,6 +42,7 @@
#include <assert.h>
#include <time.h>
#include <stdlib.h>
+#include <math.h>
#include <mathlib/math/test/test.hpp>
#include "block/Block.hpp"
diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk
index 13d1069c7..d815a8feb 100644
--- a/src/modules/controllib/module.mk
+++ b/src/modules/controllib/module.mk
@@ -37,7 +37,7 @@
SRCS = test_params.c \
block/Block.cpp \
block/BlockParam.cpp \
- block/UOrbPublication.cpp \
- block/UOrbSubscription.cpp \
- blocks.cpp \
- fixedwing.cpp
+ uorb/UOrbPublication.cpp \
+ uorb/UOrbSubscription.cpp \
+ uorb/blocks.cpp \
+ blocks.cpp
diff --git a/src/modules/controllib/block/UOrbPublication.cpp b/src/modules/controllib/uorb/UOrbPublication.cpp
index f69b39d90..f69b39d90 100644
--- a/src/modules/controllib/block/UOrbPublication.cpp
+++ b/src/modules/controllib/uorb/UOrbPublication.cpp
diff --git a/src/modules/controllib/block/UOrbPublication.hpp b/src/modules/controllib/uorb/UOrbPublication.hpp
index 0a8ae2ff7..6f1f3fc1c 100644
--- a/src/modules/controllib/block/UOrbPublication.hpp
+++ b/src/modules/controllib/uorb/UOrbPublication.hpp
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
-#include "Block.hpp"
-#include "List.hpp"
+#include "../block/Block.hpp"
+#include "../block/List.hpp"
namespace control
diff --git a/src/modules/controllib/block/UOrbSubscription.cpp b/src/modules/controllib/uorb/UOrbSubscription.cpp
index 022cadd24..022cadd24 100644
--- a/src/modules/controllib/block/UOrbSubscription.cpp
+++ b/src/modules/controllib/uorb/UOrbSubscription.cpp
diff --git a/src/modules/controllib/block/UOrbSubscription.hpp b/src/modules/controllib/uorb/UOrbSubscription.hpp
index 22cc2e114..d337d89a8 100644
--- a/src/modules/controllib/block/UOrbSubscription.hpp
+++ b/src/modules/controllib/uorb/UOrbSubscription.hpp
@@ -39,8 +39,8 @@
#pragma once
#include <uORB/uORB.h>
-#include "Block.hpp"
-#include "List.hpp"
+#include "../block/Block.hpp"
+#include "../block/List.hpp"
namespace control
diff --git a/src/modules/controllib/uorb/blocks.cpp b/src/modules/controllib/uorb/blocks.cpp
new file mode 100644
index 000000000..448a42a99
--- /dev/null
+++ b/src/modules/controllib/uorb/blocks.cpp
@@ -0,0 +1,101 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 uorb_blocks.cpp
+ *
+ * uorb block library code
+ */
+
+#include "blocks.hpp"
+
+namespace control
+{
+
+BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
+ SuperBlock(parent, name),
+ _xtYawLimit(this, "XT2YAW"),
+ _xt2Yaw(this, "XT2YAW"),
+ _psiCmd(0)
+{
+}
+
+BlockWaypointGuidance::~BlockWaypointGuidance() {};
+
+void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
+ vehicle_attitude_s &att,
+ vehicle_global_position_setpoint_s &posCmd,
+ vehicle_global_position_setpoint_s &lastPosCmd)
+{
+
+ // heading to waypoint
+ float psiTrack = get_bearing_to_next_waypoint(
+ (double)pos.lat / (double)1e7d,
+ (double)pos.lon / (double)1e7d,
+ (double)posCmd.lat / (double)1e7d,
+ (double)posCmd.lon / (double)1e7d);
+
+ // cross track
+ struct crosstrack_error_s xtrackError;
+ get_distance_to_line(&xtrackError,
+ (double)pos.lat / (double)1e7d,
+ (double)pos.lon / (double)1e7d,
+ (double)lastPosCmd.lat / (double)1e7d,
+ (double)lastPosCmd.lon / (double)1e7d,
+ (double)posCmd.lat / (double)1e7d,
+ (double)posCmd.lon / (double)1e7d);
+
+ _psiCmd = _wrap_2pi(psiTrack -
+ _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
+}
+
+BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
+ SuperBlock(parent, name),
+ // subscriptions
+ _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
+ _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
+ _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
+ _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
+ _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
+ _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
+ _status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
+ _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
+ // publications
+ _actuators(&getPublications(), ORB_ID(actuator_controls_0))
+{
+}
+
+BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
+
+} // namespace control
+
diff --git a/src/modules/controllib/uorb/blocks.hpp b/src/modules/controllib/uorb/blocks.hpp
new file mode 100644
index 000000000..9c0720aa5
--- /dev/null
+++ b/src/modules/controllib/uorb/blocks.hpp
@@ -0,0 +1,113 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 uorb_blocks.h
+ *
+ * uorb block library code
+ */
+
+#pragma once
+
+#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_rates_setpoint.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_global_position_set_triplet.h>
+#include <uORB/topics/manual_control_setpoint.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/parameter_update.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <math.h>
+
+#include <drivers/drv_hrt.h>
+#include <poll.h>
+
+extern "C" {
+#include <systemlib/geo/geo.h>
+}
+
+#include "../blocks.hpp"
+#include "UOrbSubscription.hpp"
+#include "UOrbPublication.hpp"
+
+namespace control
+{
+
+/**
+ * Waypoint Guidance block
+ */
+class __EXPORT BlockWaypointGuidance : public SuperBlock
+{
+private:
+ BlockLimitSym _xtYawLimit;
+ BlockP _xt2Yaw;
+ float _psiCmd;
+public:
+ BlockWaypointGuidance(SuperBlock *parent, const char *name);
+ virtual ~BlockWaypointGuidance();
+ void update(vehicle_global_position_s &pos,
+ vehicle_attitude_s &att,
+ vehicle_global_position_setpoint_s &posCmd,
+ vehicle_global_position_setpoint_s &lastPosCmd);
+ float getPsiCmd() { return _psiCmd; }
+};
+
+/**
+ * UorbEnabledAutopilot
+ */
+class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
+{
+protected:
+ // subscriptions
+ UOrbSubscription<vehicle_attitude_s> _att;
+ UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
+ UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
+ UOrbSubscription<vehicle_global_position_s> _pos;
+ UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
+ UOrbSubscription<manual_control_setpoint_s> _manual;
+ UOrbSubscription<vehicle_status_s> _status;
+ UOrbSubscription<parameter_update_s> _param_update;
+ // publications
+ UOrbPublication<actuator_controls_s> _actuators;
+public:
+ BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
+ virtual ~BlockUorbEnabledAutopilot();
+};
+
+} // namespace control
+
diff --git a/src/modules/controllib/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index 0cfcfd51d..16fcbd864 100644
--- a/src/modules/controllib/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -88,61 +88,6 @@ void BlockStabilization::update(float pCmd, float qCmd, float rCmd,
_yawDamper.update(rCmd, r, outputScale);
}
-BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) :
- SuperBlock(parent, name),
- _xtYawLimit(this, "XT2YAW"),
- _xt2Yaw(this, "XT2YAW"),
- _psiCmd(0)
-{
-}
-
-BlockWaypointGuidance::~BlockWaypointGuidance() {};
-
-void BlockWaypointGuidance::update(vehicle_global_position_s &pos,
- vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd)
-{
-
- // heading to waypoint
- float psiTrack = get_bearing_to_next_waypoint(
- (double)pos.lat / (double)1e7d,
- (double)pos.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
-
- // cross track
- struct crosstrack_error_s xtrackError;
- get_distance_to_line(&xtrackError,
- (double)pos.lat / (double)1e7d,
- (double)pos.lon / (double)1e7d,
- (double)lastPosCmd.lat / (double)1e7d,
- (double)lastPosCmd.lon / (double)1e7d,
- (double)posCmd.lat / (double)1e7d,
- (double)posCmd.lon / (double)1e7d);
-
- _psiCmd = _wrap_2pi(psiTrack -
- _xtYawLimit.update(_xt2Yaw.update(xtrackError.distance)));
-}
-
-BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name) :
- SuperBlock(parent, name),
- // subscriptions
- _att(&getSubscriptions(), ORB_ID(vehicle_attitude), 20),
- _attCmd(&getSubscriptions(), ORB_ID(vehicle_attitude_setpoint), 20),
- _ratesCmd(&getSubscriptions(), ORB_ID(vehicle_rates_setpoint), 20),
- _pos(&getSubscriptions() , ORB_ID(vehicle_global_position), 20),
- _posCmd(&getSubscriptions(), ORB_ID(vehicle_global_position_set_triplet), 20),
- _manual(&getSubscriptions(), ORB_ID(manual_control_setpoint), 20),
- _status(&getSubscriptions(), ORB_ID(vehicle_status), 20),
- _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
- // publications
- _actuators(&getPublications(), ORB_ID(actuator_controls_0))
-{
-}
-
-BlockUorbEnabledAutopilot::~BlockUorbEnabledAutopilot() {};
-
BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *parent, const char *name) :
BlockUorbEnabledAutopilot(parent, name),
_stabilization(this, ""), // no name needed, already unique
@@ -385,4 +330,4 @@ BlockMultiModeBacksideAutopilot::~BlockMultiModeBacksideAutopilot()
} // namespace control
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/controllib/fixedwing.hpp b/src/modules/fixedwing_backside/fixedwing.hpp
index e4028c40d..3876e4630 100644
--- a/src/modules/controllib/fixedwing.hpp
+++ b/src/modules/fixedwing_backside/fixedwing.hpp
@@ -39,31 +39,8 @@
#pragma once
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_set_triplet.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/parameter_update.h>
-
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <math.h>
-
-#include <drivers/drv_hrt.h>
-#include <poll.h>
-
-#include "blocks.hpp"
-#include "block/UOrbSubscription.hpp"
-#include "block/UOrbPublication.hpp"
-
-extern "C" {
-#include <systemlib/geo/geo.h>
-}
+#include <controllib/blocks.hpp>
+#include <controllib/uorb/blocks.hpp>
namespace control
{
@@ -251,47 +228,6 @@ public:
*/
/**
- * Waypoint Guidance block
- */
-class __EXPORT BlockWaypointGuidance : public SuperBlock
-{
-private:
- BlockLimitSym _xtYawLimit;
- BlockP _xt2Yaw;
- float _psiCmd;
-public:
- BlockWaypointGuidance(SuperBlock *parent, const char *name);
- virtual ~BlockWaypointGuidance();
- void update(vehicle_global_position_s &pos,
- vehicle_attitude_s &att,
- vehicle_global_position_setpoint_s &posCmd,
- vehicle_global_position_setpoint_s &lastPosCmd);
- float getPsiCmd() { return _psiCmd; }
-};
-
-/**
- * UorbEnabledAutopilot
- */
-class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
-{
-protected:
- // subscriptions
- UOrbSubscription<vehicle_attitude_s> _att;
- UOrbSubscription<vehicle_attitude_setpoint_s> _attCmd;
- UOrbSubscription<vehicle_rates_setpoint_s> _ratesCmd;
- UOrbSubscription<vehicle_global_position_s> _pos;
- UOrbSubscription<vehicle_global_position_set_triplet_s> _posCmd;
- UOrbSubscription<manual_control_setpoint_s> _manual;
- UOrbSubscription<vehicle_status_s> _status;
- UOrbSubscription<parameter_update_s> _param_update;
- // publications
- UOrbPublication<actuator_controls_s> _actuators;
-public:
- BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
- virtual ~BlockUorbEnabledAutopilot();
-};
-
-/**
* Multi-mode Autopilot
*/
class __EXPORT BlockMultiModeBacksideAutopilot : public BlockUorbEnabledAutopilot
diff --git a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
index 677a86771..b0de69f55 100644
--- a/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
+++ b/src/modules/fixedwing_backside/fixedwing_backside_main.cpp
@@ -45,12 +45,13 @@
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
-#include <controllib/fixedwing.hpp>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
#include <math.h>
+#include "fixedwing.hpp"
+
static bool thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
diff --git a/src/modules/fixedwing_backside/module.mk b/src/modules/fixedwing_backside/module.mk
index ec958d7cb..133728781 100644
--- a/src/modules/fixedwing_backside/module.mk
+++ b/src/modules/fixedwing_backside/module.mk
@@ -38,4 +38,5 @@
MODULE_COMMAND = fixedwing_backside
SRCS = fixedwing_backside_main.cpp \
+ fixedwing.cpp \
params.c
diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.cpp b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp
new file mode 100644
index 000000000..efb17225d
--- /dev/null
+++ b/src/modules/mathlib/math/filter/LowPassFilter2p.cpp
@@ -0,0 +1,77 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 LowPassFilter.cpp
+/// @brief A class to implement a second order low pass filter
+/// Author: Leonard Hall <LeonardTHall@gmail.com>
+
+#include "LowPassFilter2p.hpp"
+#include "math.h"
+
+namespace math
+{
+
+void LowPassFilter2p::set_cutoff_frequency(float sample_freq, float cutoff_freq)
+{
+ _cutoff_freq = cutoff_freq;
+ float fr = sample_freq/_cutoff_freq;
+ float ohm = tanf(M_PI_F/fr);
+ float c = 1.0f+2.0f*cosf(M_PI_F/4.0f)*ohm + ohm*ohm;
+ _b0 = ohm*ohm/c;
+ _b1 = 2.0f*_b0;
+ _b2 = _b0;
+ _a1 = 2.0f*(ohm*ohm-1.0f)/c;
+ _a2 = (1.0f-2.0f*cosf(M_PI_F/4.0f)*ohm+ohm*ohm)/c;
+}
+
+float LowPassFilter2p::apply(float sample)
+{
+ // do the filtering
+ float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2;
+ if (isnan(delay_element_0) || isinf(delay_element_0)) {
+ // don't allow bad values to propogate via the filter
+ delay_element_0 = sample;
+ }
+ float output = delay_element_0 * _b0 + _delay_element_1 * _b1 + _delay_element_2 * _b2;
+
+ _delay_element_2 = _delay_element_1;
+ _delay_element_1 = delay_element_0;
+
+ // return the value. Should be no need to check limits
+ return output;
+}
+
+} // namespace math
+
diff --git a/src/modules/mathlib/math/filter/LowPassFilter2p.hpp b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp
new file mode 100644
index 000000000..208ec98d4
--- /dev/null
+++ b/src/modules/mathlib/math/filter/LowPassFilter2p.hpp
@@ -0,0 +1,78 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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 LowPassFilter.h
+/// @brief A class to implement a second order low pass filter
+/// Author: Leonard Hall <LeonardTHall@gmail.com>
+/// Adapted for PX4 by Andrew Tridgell
+
+#pragma once
+
+namespace math
+{
+class __EXPORT LowPassFilter2p
+{
+public:
+ // constructor
+ LowPassFilter2p(float sample_freq, float cutoff_freq) {
+ // set initial parameters
+ set_cutoff_frequency(sample_freq, cutoff_freq);
+ _delay_element_1 = _delay_element_2 = 0;
+ }
+
+ // change parameters
+ void set_cutoff_frequency(float sample_freq, float cutoff_freq);
+
+ // apply - Add a new raw value to the filter
+ // and retrieve the filtered result
+ float apply(float sample);
+
+ // return the cutoff frequency
+ float get_cutoff_freq(void) const {
+ return _cutoff_freq;
+ }
+
+private:
+ float _cutoff_freq;
+ float _a1;
+ float _a2;
+ float _b0;
+ float _b1;
+ float _b2;
+ float _delay_element_1; // buffered sample -1
+ float _delay_element_2; // buffered sample -2
+};
+
+} // namespace math
diff --git a/src/modules/mathlib/math/filter/module.mk b/src/modules/mathlib/math/filter/module.mk
new file mode 100644
index 000000000..fe92c8c70
--- /dev/null
+++ b/src/modules/mathlib/math/filter/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.
+#
+############################################################################
+
+#
+# filter library
+#
+SRCS = LowPassFilter2p.cpp
+
+#
+# In order to include .config we first have to save off the
+# current makefile name, since app.mk needs it.
+#
+APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
+-include $(TOPDIR)/.config
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 43d96fb06..fbd82a4c6 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -300,6 +300,8 @@ controls_tick() {
} else {
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
+ } else {
+ r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE;
}
}
diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c
index ab6e3fec4..b2c0db425 100644
--- a/src/modules/px4iofirmware/dsm.c
+++ b/src/modules/px4iofirmware/dsm.c
@@ -125,9 +125,9 @@ dsm_bind(uint16_t cmd, int pulses)
case dsm_bind_send_pulses:
for (int i = 0; i < pulses; i++) {
stm32_gpiowrite(usart1RxAsOutp, false);
- up_udelay(50);
+ up_udelay(25);
stm32_gpiowrite(usart1RxAsOutp, true);
- up_udelay(50);
+ up_udelay(25);
}
break;
case dsm_bind_reinit_uart:
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index ab3983019..fefa539f9 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -606,6 +606,15 @@ int sdlog2_thread_main(int argc, char *argv[])
errx(1, "unable to create logging folder, exiting.");
}
+ const char *converter_in = "/etc/logging/conv.zip";
+ char* converter_out = malloc(150);
+ sprintf(converter_out, "%s/conv.zip", folder_path);
+
+ if (file_copy(converter_in, converter_out)) {
+ errx(1, "unable to copy conversion scripts, exiting.");
+ }
+ free(converter_out);
+
/* only print logging path, important to find log file later */
warnx("logging to directory: %s", folder_path);
@@ -1318,7 +1327,7 @@ int file_copy(const char *file_old, const char *file_new)
fclose(source);
fclose(target);
- return ret;
+ return OK;
}
void handle_command(struct vehicle_command_s *cmd)
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
new file mode 100644
index 000000000..b1dc39445
--- /dev/null
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -0,0 +1,57 @@
+#include "BlockSegwayController.hpp"
+
+void BlockSegwayController::update() {
+ // wait for a sensor update, check for exit condition every 100 ms
+ if (poll(&_attPoll, 1, 100) < 0) return; // poll error
+
+ uint64_t newTimeStamp = hrt_absolute_time();
+ float dt = (newTimeStamp - _timeStamp) / 1.0e6f;
+ _timeStamp = newTimeStamp;
+
+ // check for sane values of dt
+ // to prevent large control responses
+ if (dt > 1.0f || dt < 0) return;
+
+ // set dt for all child blocks
+ setDt(dt);
+
+ // check for new updates
+ if (_param_update.updated()) updateParams();
+
+ // get new information from subscriptions
+ updateSubscriptions();
+
+ // default all output to zero unless handled by mode
+ for (unsigned i = 2; i < NUM_ACTUATOR_CONTROLS; i++)
+ _actuators.control[i] = 0.0f;
+
+ // only update guidance in auto mode
+ if (_status.state_machine == SYSTEM_STATE_AUTO) {
+ // update guidance
+ }
+
+ // compute speed command
+ float spdCmd = -th2v.update(_att.pitch) - q2v.update(_att.pitchspeed);
+
+ // handle autopilot modes
+ if (_status.state_machine == SYSTEM_STATE_AUTO ||
+ _status.state_machine == SYSTEM_STATE_STABILIZED) {
+ _actuators.control[0] = spdCmd;
+ _actuators.control[1] = spdCmd;
+
+ } else if (_status.state_machine == SYSTEM_STATE_MANUAL) {
+ if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+ _actuators.control[CH_LEFT] = _manual.throttle;
+ _actuators.control[CH_RIGHT] = _manual.pitch;
+
+ } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
+ _actuators.control[0] = spdCmd;
+ _actuators.control[1] = spdCmd;
+ }
+ }
+
+ // update all publications
+ updatePublications();
+
+}
+
diff --git a/src/modules/segway/BlockSegwayController.hpp b/src/modules/segway/BlockSegwayController.hpp
new file mode 100644
index 000000000..4a01f785c
--- /dev/null
+++ b/src/modules/segway/BlockSegwayController.hpp
@@ -0,0 +1,27 @@
+#pragma once
+
+#include <controllib/uorb/blocks.hpp>
+
+using namespace control;
+
+class BlockSegwayController : public control::BlockUorbEnabledAutopilot {
+public:
+ BlockSegwayController() :
+ BlockUorbEnabledAutopilot(NULL,"SEG"),
+ th2v(this, "TH2V"),
+ q2v(this, "Q2V"),
+ _attPoll(),
+ _timeStamp(0)
+ {
+ _attPoll.fd = _att.getHandle();
+ _attPoll.events = POLLIN;
+ }
+ void update();
+private:
+ enum {CH_LEFT, CH_RIGHT};
+ BlockPI th2v;
+ BlockP q2v;
+ struct pollfd _attPoll;
+ uint64_t _timeStamp;
+};
+
diff --git a/src/modules/segway/module.mk b/src/modules/segway/module.mk
new file mode 100644
index 000000000..d5da85601
--- /dev/null
+++ b/src/modules/segway/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# segway controller
+#
+
+MODULE_COMMAND = segway
+
+SRCS = segway_main.cpp \
+ BlockSegwayController.cpp \
+ params.c
diff --git a/src/modules/segway/params.c b/src/modules/segway/params.c
new file mode 100644
index 000000000..d72923717
--- /dev/null
+++ b/src/modules/segway/params.c
@@ -0,0 +1,8 @@
+#include <systemlib/param/param.h>
+
+// 16 is max name length
+PARAM_DEFINE_FLOAT(SEG_TH2V_P, 10.0f); // pitch to voltage
+PARAM_DEFINE_FLOAT(SEG_TH2V_I, 0.0f); // pitch integral to voltage
+PARAM_DEFINE_FLOAT(SEG_TH2V_I_MAX, 0.0f); // integral limiter
+PARAM_DEFINE_FLOAT(SEG_Q2V, 1.0f); // pitch rate to voltage
+
diff --git a/src/modules/segway/segway_main.cpp b/src/modules/segway/segway_main.cpp
new file mode 100644
index 000000000..061fbf9b9
--- /dev/null
+++ b/src/modules/segway/segway_main.cpp
@@ -0,0 +1,157 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Author: James Goppert
+ *
+ * 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 segway_main.cpp
+ * @author James Goppert
+ *
+ * Segway controller using control library
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <math.h>
+
+#include "BlockSegwayController.hpp"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int deamon_task; /**< Handle of deamon task / thread */
+
+/**
+ * Deamon management function.
+ */
+extern "C" __EXPORT int segway_main(int argc, char *argv[]);
+
+/**
+ * Mainloop of deamon.
+ */
+int segway_thread_main(int argc, char *argv[]);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason);
+
+static void
+usage(const char *reason)
+{
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+
+ fprintf(stderr, "usage: segway {start|stop|status} [-p <additional params>]\n\n");
+ exit(1);
+}
+
+/**
+ * The deamon app only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int segway_main(int argc, char *argv[])
+{
+
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (thread_running) {
+ warnx("already running");
+ /* this is not an error */
+ exit(0);
+ }
+
+ thread_should_exit = false;
+
+ deamon_task = task_spawn_cmd("segway",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 10,
+ 5120,
+ segway_thread_main,
+ (argv) ? (const char **)&argv[2] : (const char **)NULL);
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ warnx("is running");
+
+ } else {
+ warnx("not started");
+ }
+
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+int segway_thread_main(int argc, char *argv[])
+{
+
+ warnx("starting");
+
+ using namespace control;
+
+ BlockSegwayController autopilot;
+
+ thread_running = true;
+
+ while (!thread_should_exit) {
+ autopilot.update();
+ }
+
+ warnx("exiting.");
+
+ thread_running = false;
+
+ return 0;
+}
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index d0af9e17b..2bd869263 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);
@@ -156,6 +156,7 @@ PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f);
PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */
PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */
+PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */
/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */
PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f));
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index b38dc8d89..22374a1fe 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>
@@ -91,8 +92,35 @@
#define BARO_HEALTH_COUNTER_LIMIT_OK 5
#define ADC_HEALTH_COUNTER_LIMIT_OK 5
-#define ADC_BATTERY_VOLTAGE_CHANNEL 10
-#define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
+/**
+ * Analog layout:
+ * FMU:
+ * IN2 - battery voltage
+ * IN3 - battery current
+ * IN4 - 5V sense
+ * IN10 - spare (we could actually trim these from the set)
+ * IN11 - spare (we could actually trim these from the set)
+ * IN12 - spare (we could actually trim these from the set)
+ * IN13 - aux1
+ * IN14 - aux2
+ * IN15 - pressure sensor
+ *
+ * IO:
+ * IN4 - servo supply rail
+ * IN5 - analog RSSI
+ */
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+ #define ADC_BATTERY_VOLTAGE_CHANNEL 10
+ #define ADC_AIRSPEED_VOLTAGE_CHANNEL 11
+#endif
+
+#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
+ #define ADC_BATTERY_VOLTAGE_CHANNEL 2
+ #define ADC_BATTERY_CURRENT_CHANNEL 3
+ #define ADC_5V_RAIL_SENSE 4
+ #define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
+#endif
#define BAT_VOL_INITIAL 0.f
#define BAT_VOL_LOWPASS_1 0.99f
@@ -197,7 +225,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;
@@ -228,7 +256,6 @@ private:
float battery_voltage_scaling;
- int rc_rl1_DSM_VCC_control;
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -277,7 +304,6 @@ private:
param_t battery_voltage_scaling;
- param_t rc_rl1_DSM_VCC_control;
} _parameter_handles; /**< handles for interesting parameters */
@@ -389,7 +415,7 @@ namespace sensors
#endif
static const int ERROR = -1;
-Sensors *g_sensors;
+Sensors *g_sensors = nullptr;
}
Sensors::Sensors() :
@@ -512,9 +538,6 @@ Sensors::Sensors() :
_parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING");
- /* DSM VCC relay control */
- _parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC");
-
/* fetch initial parameter values */
parameters_update();
}
@@ -552,25 +575,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]);
@@ -656,21 +665,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;
@@ -726,11 +724,6 @@ Sensors::parameters_update()
warnx("Failed updating voltage scaling param");
}
- /* relay 1 DSM VCC control */
- if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) {
- warnx("Failed updating relay 1 DSM VCC control");
- }
-
return OK;
}
@@ -746,11 +739,26 @@ Sensors::accel_init()
errx(1, "FATAL: no accelerometer found");
} else {
- /* set the accel internal sampling rate up to at leat 500Hz */
- ioctl(fd, ACCELIOCSSAMPLERATE, 500);
- /* set the driver to poll at 500Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, 500);
+ // XXX do the check more elegantly
+
+ #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* set the accel internal sampling rate up to at leat 1000Hz */
+ ioctl(fd, ACCELIOCSSAMPLERATE, 1000);
+
+ /* set the driver to poll at 1000Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 1000);
+
+ #else
+
+ /* set the accel internal sampling rate up to at leat 800Hz */
+ ioctl(fd, ACCELIOCSSAMPLERATE, 800);
+
+ /* set the driver to poll at 800Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 800);
+
+ #endif
warnx("using system accel");
close(fd);
@@ -769,11 +777,28 @@ Sensors::gyro_init()
errx(1, "FATAL: no gyro found");
} else {
- /* set the gyro internal sampling rate up to at leat 500Hz */
- ioctl(fd, GYROIOCSSAMPLERATE, 500);
- /* set the driver to poll at 500Hz */
- ioctl(fd, SENSORIOCSPOLLRATE, 500);
+ // XXX do the check more elegantly
+
+ #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
+
+ /* set the gyro internal sampling rate up to at least 1000Hz */
+ if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
+ ioctl(fd, GYROIOCSSAMPLERATE, 800);
+
+ /* set the driver to poll at 1000Hz */
+ if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
+ ioctl(fd, SENSORIOCSPOLLRATE, 800);
+
+ #else
+
+ /* set the gyro internal sampling rate up to at leat 800Hz */
+ ioctl(fd, GYROIOCSSAMPLERATE, 800);
+
+ /* set the driver to poll at 800Hz */
+ ioctl(fd, SENSORIOCSPOLLRATE, 800);
+
+ #endif
warnx("using system gyro");
close(fd);
@@ -1034,6 +1059,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]);
@@ -1364,6 +1403,9 @@ Sensors::task_main()
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vcontrol_mode_sub, 200);
+ /* rate limit gyro to 250 Hz (the gyro signal is lowpassed accordingly earlier) */
+ orb_set_interval(_gyro_sub, 4);
+
/*
* do advertisements
*/
@@ -1399,7 +1441,7 @@ Sensors::task_main()
while (!_task_should_exit) {
- /* wait for up to 500ms for data */
+ /* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
/* timed out - periodic check for _task_should_exit, etc. */
diff --git a/src/modules/systemlib/hx_stream.c b/src/modules/systemlib/hx_stream.c
index 8d77f14a8..8e9c2bfcf 100644
--- a/src/modules/systemlib/hx_stream.c
+++ b/src/modules/systemlib/hx_stream.c
@@ -53,14 +53,26 @@
struct hx_stream {
- uint8_t buf[HX_STREAM_MAX_FRAME + 4];
- unsigned frame_bytes;
- bool escaped;
- bool txerror;
-
+ /* RX state */
+ uint8_t rx_buf[HX_STREAM_MAX_FRAME + 4];
+ unsigned rx_frame_bytes;
+ bool rx_escaped;
+ hx_stream_rx_callback rx_callback;
+ void *rx_callback_arg;
+
+ /* TX state */
int fd;
- hx_stream_rx_callback callback;
- void *callback_arg;
+ bool tx_error;
+ uint8_t *tx_buf;
+ unsigned tx_resid;
+ uint32_t tx_crc;
+ enum {
+ TX_IDLE = 0,
+ TX_SEND_START,
+ TX_SEND_DATA,
+ TX_SENT_ESCAPE,
+ TX_SEND_END
+ } tx_state;
perf_counter_t pc_tx_frames;
perf_counter_t pc_rx_frames;
@@ -81,21 +93,7 @@ static void
hx_tx_raw(hx_stream_t stream, uint8_t c)
{
if (write(stream->fd, &c, 1) != 1)
- stream->txerror = true;
-}
-
-static void
-hx_tx_byte(hx_stream_t stream, uint8_t c)
-{
- switch (c) {
- case FBO:
- case CEO:
- hx_tx_raw(stream, CEO);
- c ^= 0x20;
- break;
- }
-
- hx_tx_raw(stream, c);
+ stream->tx_error = true;
}
static int
@@ -105,11 +103,11 @@ hx_rx_frame(hx_stream_t stream)
uint8_t b[4];
uint32_t w;
} u;
- unsigned length = stream->frame_bytes;
+ unsigned length = stream->rx_frame_bytes;
/* reset the stream */
- stream->frame_bytes = 0;
- stream->escaped = false;
+ stream->rx_frame_bytes = 0;
+ stream->rx_escaped = false;
/* not a real frame - too short */
if (length < 4) {
@@ -122,11 +120,11 @@ hx_rx_frame(hx_stream_t stream)
length -= 4;
/* compute expected CRC */
- u.w = crc32(&stream->buf[0], length);
+ u.w = crc32(&stream->rx_buf[0], length);
/* compare computed and actual CRC */
for (unsigned i = 0; i < 4; i++) {
- if (u.b[i] != stream->buf[length + i]) {
+ if (u.b[i] != stream->rx_buf[length + i]) {
perf_count(stream->pc_rx_errors);
return 0;
}
@@ -134,7 +132,7 @@ hx_rx_frame(hx_stream_t stream)
/* frame is good */
perf_count(stream->pc_rx_frames);
- stream->callback(stream->callback_arg, &stream->buf[0], length);
+ stream->rx_callback(stream->rx_callback_arg, &stream->rx_buf[0], length);
return 1;
}
@@ -150,8 +148,8 @@ hx_stream_init(int fd,
if (stream != NULL) {
memset(stream, 0, sizeof(struct hx_stream));
stream->fd = fd;
- stream->callback = callback;
- stream->callback_arg = arg;
+ stream->rx_callback = callback;
+ stream->rx_callback_arg = arg;
}
return stream;
@@ -179,49 +177,112 @@ hx_stream_set_counters(hx_stream_t stream,
stream->pc_rx_errors = rx_errors;
}
+void
+hx_stream_reset(hx_stream_t stream)
+{
+ stream->rx_frame_bytes = 0;
+ stream->rx_escaped = false;
+
+ stream->tx_buf = NULL;
+ stream->tx_resid = 0;
+ stream->tx_state = TX_IDLE;
+}
+
int
-hx_stream_send(hx_stream_t stream,
+hx_stream_start(hx_stream_t stream,
const void *data,
size_t count)
{
- union {
- uint8_t b[4];
- uint32_t w;
- } u;
- const uint8_t *p = (const uint8_t *)data;
- unsigned resid = count;
-
- if (resid > HX_STREAM_MAX_FRAME)
+ if (count > HX_STREAM_MAX_FRAME)
return -EINVAL;
- /* start the frame */
- hx_tx_raw(stream, FBO);
+ stream->tx_buf = data;
+ stream->tx_resid = count;
+ stream->tx_state = TX_SEND_START;
+ stream->tx_crc = crc32(data, count);
+ return OK;
+}
+
+int
+hx_stream_send_next(hx_stream_t stream)
+{
+ int c;
+
+ /* sort out what we're going to send */
+ switch (stream->tx_state) {
- /* transmit the data */
- while (resid--)
- hx_tx_byte(stream, *p++);
+ case TX_SEND_START:
+ stream->tx_state = TX_SEND_DATA;
+ return FBO;
- /* compute the CRC */
- u.w = crc32(data, count);
+ case TX_SEND_DATA:
+ c = *stream->tx_buf;
- /* send the CRC */
- p = &u.b[0];
- resid = 4;
+ switch (c) {
+ case FBO:
+ case CEO:
+ stream->tx_state = TX_SENT_ESCAPE;
+ return CEO;
+ }
+ break;
+
+ case TX_SENT_ESCAPE:
+ c = *stream->tx_buf ^ 0x20;
+ stream->tx_state = TX_SEND_DATA;
+ break;
+
+ case TX_SEND_END:
+ stream->tx_state = TX_IDLE;
+ return FBO;
+
+ case TX_IDLE:
+ default:
+ return -1;
+ }
+
+ /* if we are here, we have consumed a byte from the buffer */
+ stream->tx_resid--;
+ stream->tx_buf++;
+
+ /* buffer exhausted */
+ if (stream->tx_resid == 0) {
+ uint8_t *pcrc = (uint8_t *)&stream->tx_crc;
+
+ /* was the buffer the frame CRC? */
+ if (stream->tx_buf == (pcrc + sizeof(stream->tx_crc))) {
+ stream->tx_state = TX_SEND_END;
+ } else {
+ /* no, it was the payload - switch to sending the CRC */
+ stream->tx_buf = pcrc;
+ stream->tx_resid = sizeof(stream->tx_crc);
+ }
+ }
+ return c;
+}
+
+int
+hx_stream_send(hx_stream_t stream,
+ const void *data,
+ size_t count)
+{
+ int result;
- while (resid--)
- hx_tx_byte(stream, *p++);
+ result = hx_stream_start(stream, data, count);
+ if (result != OK)
+ return result;
- /* and the trailing frame separator */
- hx_tx_raw(stream, FBO);
+ int c;
+ while ((c = hx_stream_send_next(stream)) >= 0)
+ hx_tx_raw(stream, c);
/* check for transmit error */
- if (stream->txerror) {
- stream->txerror = false;
+ if (stream->tx_error) {
+ stream->tx_error = false;
return -EIO;
}
perf_count(stream->pc_tx_frames);
- return 0;
+ return OK;
}
void
@@ -234,17 +295,17 @@ hx_stream_rx(hx_stream_t stream, uint8_t c)
}
/* escaped? */
- if (stream->escaped) {
- stream->escaped = false;
+ if (stream->rx_escaped) {
+ stream->rx_escaped = false;
c ^= 0x20;
} else if (c == CEO) {
- /* now escaped, ignore the byte */
- stream->escaped = true;
+ /* now rx_escaped, ignore the byte */
+ stream->rx_escaped = true;
return;
}
/* save for later */
- if (stream->frame_bytes < sizeof(stream->buf))
- stream->buf[stream->frame_bytes++] = c;
+ if (stream->rx_frame_bytes < sizeof(stream->rx_buf))
+ stream->rx_buf[stream->rx_frame_bytes++] = c;
}
diff --git a/src/modules/systemlib/hx_stream.h b/src/modules/systemlib/hx_stream.h
index 128689953..1f3927222 100644
--- a/src/modules/systemlib/hx_stream.h
+++ b/src/modules/systemlib/hx_stream.h
@@ -58,7 +58,8 @@ __BEGIN_DECLS
* Allocate a new hx_stream object.
*
* @param fd The file handle over which the protocol will
- * communicate.
+ * communicate, or -1 if the protocol will use
+ * hx_stream_start/hx_stream_send_next.
* @param callback Called when a frame is received.
* @param callback_arg Passed to the callback.
* @return A handle to the stream, or NULL if memory could
@@ -80,6 +81,7 @@ __EXPORT extern void hx_stream_free(hx_stream_t stream);
*
* Any counter may be set to NULL to disable counting that datum.
*
+ * @param stream A handle returned from hx_stream_init.
* @param tx_frames Counter for transmitted frames.
* @param rx_frames Counter for received frames.
* @param rx_errors Counter for short and corrupt received frames.
@@ -90,6 +92,44 @@ __EXPORT extern void hx_stream_set_counters(hx_stream_t stream,
perf_counter_t rx_errors);
/**
+ * Reset a stream.
+ *
+ * Forces the local stream state to idle.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ */
+__EXPORT extern void hx_stream_reset(hx_stream_t stream);
+
+/**
+ * Prepare to send a frame.
+ *
+ * Use this in conjunction with hx_stream_send_next to
+ * set the frame to be transmitted.
+ *
+ * Use hx_stream_send() to write to the stream fd directly.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ * @param data Pointer to the data to send.
+ * @param count The number of bytes to send.
+ * @return Zero on success, -errno on error.
+ */
+__EXPORT extern int hx_stream_start(hx_stream_t stream,
+ const void *data,
+ size_t count);
+
+/**
+ * Get the next byte to send for a stream.
+ *
+ * This requires that the stream be prepared for sending by
+ * calling hx_stream_start first.
+ *
+ * @param stream A handle returned from hx_stream_init.
+ * @return The byte to send, or -1 if there is
+ * nothing left to send.
+ */
+__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
+
+/**
* Send a frame.
*
* This function will block until all frame bytes are sent if
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index 879f4715a..3c1e10287 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -201,23 +201,50 @@ perf_end(perf_counter_t handle)
switch (handle->type) {
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
- pce->event_count++;
- pce->time_total += elapsed;
+ if (pce->time_start != 0) {
+ hrt_abstime elapsed = hrt_absolute_time() - pce->time_start;
- if ((pce->time_least > elapsed) || (pce->time_least == 0))
- pce->time_least = elapsed;
+ pce->event_count++;
+ pce->time_total += elapsed;
- if (pce->time_most < elapsed)
- pce->time_most = elapsed;
+ if ((pce->time_least > elapsed) || (pce->time_least == 0))
+ pce->time_least = elapsed;
+
+ if (pce->time_most < elapsed)
+ pce->time_most = elapsed;
+
+ pce->time_start = 0;
+ }
+ }
+ break;
+
+ default:
+ break;
+ }
+}
+
+void
+perf_cancel(perf_counter_t handle)
+{
+ if (handle == NULL)
+ return;
+
+ switch (handle->type) {
+ case PC_ELAPSED: {
+ struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
+
+ pce->time_start = 0;
}
+ break;
default:
break;
}
}
+
+
void
perf_reset(perf_counter_t handle)
{
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index 5c2cb15b2..4cd8b67a1 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -92,13 +92,25 @@ __EXPORT extern void perf_begin(perf_counter_t handle);
* End a performance event.
*
* This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
+ * If a call is made without a corresopnding perf_begin call, or if perf_cancel
+ * has been called subsequently, no change is made to the counter.
*
* @param handle The handle returned from perf_alloc.
*/
__EXPORT extern void perf_end(perf_counter_t handle);
/**
- * Reset a performance event.
+ * Cancel a performance event.
+ *
+ * This call applies to counters that operate over ranges of time; PC_ELAPSED etc.
+ * It reverts the effect of a previous perf_begin.
+ *
+ * @param handle The handle returned from perf_alloc.
+ */
+__EXPORT extern void perf_cancel(perf_counter_t handle);
+
+/**
+ * Reset a performance counter.
*
* This call resets performance counter to initial state
*
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
diff --git a/src/systemcmds/tests/test_hrt.c b/src/systemcmds/tests/test_hrt.c
index f21dd115b..f6e540401 100644
--- a/src/systemcmds/tests/test_hrt.c
+++ b/src/systemcmds/tests/test_hrt.c
@@ -94,7 +94,7 @@ extern uint16_t ppm_pulse_history[];
int test_ppm(int argc, char *argv[])
{
-#ifdef CONFIG_HRT_PPM
+#ifdef HRT_PPM_CHANNEL
unsigned i;
printf("channels: %u\n", ppm_decoded_channels);