aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2014-05-26 20:19:11 +0200
committerJulian Oes <julian@oes.ch>2014-05-26 20:19:11 +0200
commit063caba36bd2fe26eb4bfa8e546e9551ccc05519 (patch)
treed8ea5015111793800d945fbc33505088cf5fe12d
parent68352cb923d366b66bb68c8d946c4960b6f7ff1a (diff)
parent36495cdb62e21b30a5a1851ec802c9f6a40c1171 (diff)
downloadpx4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.tar.gz
px4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.tar.bz2
px4-firmware-063caba36bd2fe26eb4bfa8e546e9551ccc05519.zip
Merge branch 'master' into navigator_rewrite
Conflicts: src/drivers/gps/gps.cpp src/drivers/gps/mtk.cpp src/modules/commander/commander.cpp src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp src/modules/navigator/mission.cpp src/modules/navigator/mission.h src/modules/navigator/navigator_main.cpp src/modules/navigator/navigator_state.h src/modules/position_estimator_inav/position_estimator_inav_main.c
-rw-r--r--Documentation/rc_mode_switch.odgbin22421 -> 33043 bytes
-rw-r--r--Documentation/rc_mode_switch.pdfbin29666 -> 26949 bytes
-rw-r--r--Images/aerocore.prototype12
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris6
-rw-r--r--ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d35
-rw-r--r--ROMFS/px4fmu_common/init.d/11001_hexa_cox2
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.autostart5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_defaults2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging4
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.usb10
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS20
-rwxr-xr-xTools/fix_code_style.sh3
-rw-r--r--makefiles/board_aerocore.mk11
-rw-r--r--makefiles/config_aerocore_default.mk125
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk14
-rw-r--r--nuttx-configs/aerocore/include/board.h263
-rw-r--r--nuttx-configs/aerocore/include/nsh_romfsimg.h42
-rw-r--r--nuttx-configs/aerocore/nsh/Make.defs179
-rw-r--r--nuttx-configs/aerocore/nsh/appconfig (renamed from src/examples/flow_position_control/module.mk)17
-rw-r--r--nuttx-configs/aerocore/nsh/defconfig950
-rwxr-xr-xnuttx-configs/aerocore/nsh/setenv.sh67
-rw-r--r--nuttx-configs/aerocore/scripts/ld.script150
-rw-r--r--nuttx-configs/aerocore/src/Makefile84
-rw-r--r--nuttx-configs/aerocore/src/empty.c4
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig14
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/ardrone_interface/module.mk1
-rw-r--r--src/drivers/blinkm/blinkm.cpp71
-rw-r--r--src/drivers/boards/aerocore/aerocore_init.c282
-rw-r--r--src/drivers/boards/aerocore/aerocore_led.c (renamed from src/examples/flow_position_control/flow_position_control_params.h)147
-rw-r--r--src/drivers/boards/aerocore/aerocore_pwm_servo.c117
-rw-r--r--src/drivers/boards/aerocore/aerocore_spi.c183
-rw-r--r--src/drivers/boards/aerocore/board_config.h176
-rw-r--r--src/drivers/boards/aerocore/module.mk8
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h2
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/drivers/drv_gpio.h10
-rw-r--r--src/drivers/drv_gps.h4
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp10
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.c17
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c2
-rw-r--r--src/drivers/frsky_telemetry/module.mk2
-rw-r--r--src/drivers/gps/gps.cpp29
-rw-r--r--src/drivers/gps/gps_helper.cpp4
-rw-r--r--src/drivers/gps/gps_helper.h8
-rw-r--r--src/drivers/gps/module.mk2
-rw-r--r--src/drivers/gps/mtk.cpp10
-rw-r--r--src/drivers/gps/ubx.cpp47
-rw-r--r--src/drivers/gps/ubx.h28
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp10
-rw-r--r--src/drivers/hott/messages.cpp32
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp56
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp38
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp1
-rw-r--r--src/drivers/ms5611/ms5611.cpp4
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp97
-rw-r--r--src/drivers/px4fmu/module.mk2
-rw-r--r--src/drivers/px4io/module.mk2
-rw-r--r--src/drivers/px4io/px4io.cpp61
-rw-r--r--src/drivers/px4io/px4io_serial.cpp2
-rw-r--r--src/drivers/sf0x/sf0x.cpp7
-rw-r--r--src/drivers/stm32/adc/adc.cpp6
-rw-r--r--src/drivers/stm32/drv_hrt.c14
-rw-r--r--src/examples/fixedwing_control/module.mk2
-rw-r--r--src/examples/flow_position_control/flow_position_control_main.c613
-rw-r--r--src/examples/flow_position_control/flow_position_control_params.c124
-rw-r--r--src/examples/flow_position_estimator/flow_position_estimator_main.c5
-rw-r--r--src/examples/px4_daemon_app/module.mk2
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c2
-rw-r--r--src/examples/px4_mavlink_debug/module.mk4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp21
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp23
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp20
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h4
-rw-r--r--src/lib/version/version.h4
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp25
-rw-r--r--src/modules/attitude_estimator_ekf/module.mk2
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp9
-rw-r--r--src/modules/attitude_estimator_so3/module.mk2
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp66
-rw-r--r--src/modules/commander/airspeed_calibration.cpp6
-rw-r--r--src/modules/commander/commander.cpp367
-rw-r--r--src/modules/commander/commander_helper.cpp22
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp24
-rw-r--r--src/modules/commander/gyro_calibration.cpp18
-rw-r--r--src/modules/commander/mag_calibration.cpp47
-rw-r--r--src/modules/commander/module.mk4
-rw-r--r--src/modules/commander/px4_custom_mode.h5
-rw-r--r--src/modules/commander/rc_calibration.cpp6
-rw-r--r--src/modules/commander/state_machine_helper.cpp166
-rw-r--r--src/modules/dataman/dataman.c52
-rw-r--r--src/modules/dataman/dataman.h20
-rw-r--r--src/modules/dataman/module.mk2
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp (renamed from src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp)56
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c (renamed from src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c)6
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator.cpp89
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator.h1
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk6
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp4
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp88
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp152
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c11
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.cpp34
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.h31
-rw-r--r--src/modules/mavlink/mavlink_main.cpp23
-rw-r--r--src/modules/mavlink/mavlink_main.h5
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp20
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.cpp2
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.h2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp14
-rw-r--r--src/modules/mavlink/mavlink_stream.cpp4
-rw-r--r--src/modules/mavlink/mavlink_stream.h6
-rw-r--r--src/modules/mavlink/module.mk2
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp105
-rw-r--r--src/modules/mc_att_control/mc_att_control_params.c48
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp12
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_params.c12
-rw-r--r--src/modules/navigator/geofence.cpp5
-rw-r--r--src/modules/navigator/geofence.h5
-rw-r--r--src/modules/navigator/mission.cpp4
-rw-r--r--src/modules/navigator/mission.h2
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp13
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h6
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator_main.cpp12
-rw-r--r--src/modules/navigator/navigator_params.c3
-rw-r--r--src/modules/position_estimator_inav/module.mk2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c23
-rw-r--r--src/modules/px4iofirmware/controls.c7
-rw-r--r--src/modules/px4iofirmware/mixer.cpp1
-rw-r--r--src/modules/px4iofirmware/protocol.h14
-rw-r--r--src/modules/px4iofirmware/registers.c24
-rw-r--r--src/modules/sdlog2/module.mk2
-rw-r--r--src/modules/sdlog2/sdlog2.c230
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h41
-rw-r--r--src/modules/segway/BlockSegwayController.cpp4
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c132
-rw-r--r--src/modules/sensors/sensors.cpp264
-rw-r--r--src/modules/systemlib/mixer/mixer.h3
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp112
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables15
-rw-r--r--src/modules/systemlib/param/param.c64
-rw-r--r--src/modules/systemlib/perf_counter.c16
-rw-r--r--src/modules/systemlib/perf_counter.h14
-rw-r--r--src/modules/systemlib/pid/pid.c2
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c14
-rw-r--r--src/modules/systemlib/rc_check.c2
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h44
-rw-r--r--src/modules/uORB/topics/rc_channels.h19
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h5
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_status.h5
-rw-r--r--src/systemcmds/config/config.c43
-rw-r--r--src/systemcmds/mtd/24xxxx_mtd.c36
-rw-r--r--src/systemcmds/mtd/mtd.c4
-rw-r--r--src/systemcmds/nshterm/module.mk2
-rw-r--r--src/systemcmds/param/module.mk3
-rw-r--r--src/systemcmds/param/param.c39
-rw-r--r--src/systemcmds/perf/module.mk2
-rw-r--r--src/systemcmds/perf/perf.c2
-rw-r--r--src/systemcmds/preflight_check/module.mk2
-rw-r--r--src/systemcmds/pwm/module.mk2
-rw-r--r--src/systemcmds/reboot/module.mk2
-rw-r--r--src/systemcmds/tests/test_mtd.c17
-rw-r--r--src/systemcmds/tests/tests_main.c2
-rw-r--r--src/systemcmds/top/module.mk2
173 files changed, 5313 insertions, 1891 deletions
diff --git a/Documentation/rc_mode_switch.odg b/Documentation/rc_mode_switch.odg
index 1ef05458f..682c63e47 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 b1a468d17..e795f4870 100644
--- a/Documentation/rc_mode_switch.pdf
+++ b/Documentation/rc_mode_switch.pdf
Binary files differ
diff --git a/Images/aerocore.prototype b/Images/aerocore.prototype
new file mode 100644
index 000000000..8502a0864
--- /dev/null
+++ b/Images/aerocore.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 19,
+ "magic": "AeroCore",
+ "description": "Firmware for the Gumstix AeroCore board",
+ "image": "",
+ "build_time": 0,
+ "summary": "AEROCORE",
+ "version": "0.1",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
index f11aa704e..084dff140 100644
--- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris
+++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris
@@ -18,9 +18,9 @@ then
param set MC_PITCHRATE_P 0.13
param set MC_PITCHRATE_I 0.0
param set MC_PITCHRATE_D 0.004
- param set MC_YAW_P 0.5
- param set MC_YAWRATE_P 0.2
- param set MC_YAWRATE_I 0.0
+ param set MC_YAW_P 2.5
+ param set MC_YAWRATE_P 0.25
+ param set MC_YAWRATE_I 0.25
param set MC_YAWRATE_D 0.0
param set BAT_V_SCALING 0.00989
diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
new file mode 100644
index 000000000..6179855f6
--- /dev/null
+++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
@@ -0,0 +1,35 @@
+#!nsh
+#
+# Steadidrone QU4D
+#
+# Thomas Gubler <thomasgubler@gmail.com>
+# Lorenz Meier <lm@inf.ethz.ch>
+#
+
+sh /etc/init.d/rc.mc_defaults
+
+if [ $DO_AUTOCONFIG == yes ]
+then
+ # TODO tune roll/pitch separately
+ param set MC_ROLL_P 7.0
+ param set MC_ROLLRATE_P 0.13
+ param set MC_ROLLRATE_I 0.0
+ param set MC_ROLLRATE_D 0.004
+ param set MC_PITCH_P 7.0
+ param set MC_PITCHRATE_P 0.13
+ param set MC_PITCHRATE_I 0.0
+ param set MC_PITCHRATE_D 0.004
+ param set MC_YAW_P 0.5
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.0
+ param set MC_YAWRATE_D 0.0
+
+ param set BAT_N_CELLS 4
+fi
+
+set MIXER FMU_quad_w
+
+set PWM_MIN 1210
+set PWM_MAX 2100
+
+set PWM_OUTPUTS 1234
diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
index df2e609bc..daa04a4de 100644
--- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox
+++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox
@@ -1,7 +1,5 @@
#!nsh
#
-# UNTESTED UNTESTED!
-#
# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
index db0e40fc2..3ab2ac3d1 100644
--- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
+++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar
@@ -5,4 +5,4 @@
sh /etc/init.d/rc.fw_defaults
-set MIXER easystar.mix
+set MIXER easystar
diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart
index 5ec735d39..b365bd642 100644
--- a/ROMFS/px4fmu_common/init.d/rc.autostart
+++ b/ROMFS/px4fmu_common/init.d/rc.autostart
@@ -195,6 +195,11 @@ then
sh /etc/init.d/10016_3dr_iris
fi
+if param compare SYS_AUTOSTART 10017
+then
+ sh /etc/init.d/10017_steadidrone_qu4d
+fi
+
#
# Hexa Coaxial
#
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
index 4cd73e23f..3a50fcf56 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults
@@ -11,6 +11,4 @@ then
param set NAV_RTL_ALT 100
param set NAV_RTL_LAND_T -1
param set NAV_ACCEPT_RAD 50
- param set RC_SCALE_ROLL 1
- param set RC_SCALE_PITCH 1
fi \ No newline at end of file
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 3469d5f5f..25f31a7e0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -8,9 +8,9 @@ then
if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
- sdlog2 start -r 50 -a -b 8 -t
+ sdlog2 start -r 50 -a -b 4 -t
else
echo "Start sdlog2 at 200Hz"
- sdlog2 start -r 200 -a -b 16 -t
+ sdlog2 start -r 200 -a -b 22 -t
fi
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb
index b7b556945..76593881d 100644
--- a/ROMFS/px4fmu_common/init.d/rc.usb
+++ b/ROMFS/px4fmu_common/init.d/rc.usb
@@ -3,16 +3,20 @@
# USB MAVLink start
#
-echo "Starting MAVLink on this USB console"
-
mavlink start -r 10000 -d /dev/ttyACM0
# Enable a number of interesting streams we want via USB
mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s VFR_HUD -r 20
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20
+usleep 100000
mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30
-mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 10
+usleep 100000
+mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
+usleep 100000
# Exit shell to make it available to MAVLink
exit
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 756ee8ef8..8c413e087 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -420,16 +420,6 @@ then
mavlink start $MAVLINK_FLAGS
#
- # Start the datamanager
- #
- dataman start
-
- #
- # Start the navigator
- #
- navigator start
-
- #
# Sensors, Logging, GPS
#
sh /etc/init.d/rc.sensors
@@ -551,6 +541,16 @@ then
fi
#
+ # Start the datamanager
+ #
+ dataman start
+
+ #
+ # Start the navigator
+ #
+ navigator start
+
+ #
# Generic setup (autostart ID not found)
#
if [ $VEHICLE_TYPE == none ]
diff --git a/Tools/fix_code_style.sh b/Tools/fix_code_style.sh
index 0b6743013..5995d428e 100755
--- a/Tools/fix_code_style.sh
+++ b/Tools/fix_code_style.sh
@@ -16,5 +16,6 @@ astyle \
--ignore-exclude-errors-x \
--lineend=linux \
--exclude=EASTL \
- --add-brackets \
+ --add-brackets \
+ --max-code-length=120 \
$*
diff --git a/makefiles/board_aerocore.mk b/makefiles/board_aerocore.mk
new file mode 100644
index 000000000..6f4b93266
--- /dev/null
+++ b/makefiles/board_aerocore.mk
@@ -0,0 +1,11 @@
+#
+# Board-specific definitions for the Gumstix AeroCore
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM4F
+CONFIG_BOARD = AEROCORE
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_aerocore_default.mk b/makefiles/config_aerocore_default.mk
new file mode 100644
index 000000000..d6902c4ee
--- /dev/null
+++ b/makefiles/config_aerocore_default.mk
@@ -0,0 +1,125 @@
+#
+# Makefile for the AeroCore *default* configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+
+#
+# Board support modules
+#
+MODULES += drivers/device
+MODULES += drivers/stm32
+MODULES += drivers/stm32/adc
+MODULES += drivers/stm32/tone_alarm
+MODULES += drivers/led
+MODULES += drivers/px4fmu
+MODULES += drivers/boards/aerocore
+MODULES += drivers/lsm303d
+MODULES += drivers/l3gd20
+MODULES += drivers/ms5611
+MODULES += drivers/gps
+MODULES += drivers/hil
+MODULES += modules/sensors
+
+#
+# System commands
+#
+MODULES += systemcmds/boardinfo
+MODULES += systemcmds/mixer
+MODULES += systemcmds/param
+MODULES += systemcmds/perf
+MODULES += systemcmds/preflight_check
+MODULES += systemcmds/pwm
+MODULES += systemcmds/esc_calib
+MODULES += systemcmds/reboot
+MODULES += systemcmds/top
+MODULES += systemcmds/config
+MODULES += systemcmds/nshterm
+MODULES += systemcmds/mtd
+MODULES += systemcmds/dumpfile
+
+#
+# General system control
+#
+MODULES += modules/commander
+MODULES += modules/navigator
+MODULES += modules/mavlink
+
+#
+# Estimation modules (EKF/ SO3 / other filters)
+#
+MODULES += modules/attitude_estimator_ekf
+MODULES += modules/attitude_estimator_so3
+MODULES += modules/ekf_att_pos_estimator
+MODULES += modules/position_estimator_inav
+
+#
+# Vehicle Control
+#
+MODULES += modules/fw_pos_control_l1
+MODULES += modules/fw_att_control
+MODULES += modules/mc_att_control
+MODULES += modules/mc_pos_control
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
+MODULES += modules/controllib
+MODULES += modules/uORB
+MODULES += modules/dataman
+
+#
+# Libraries
+#
+LIBRARIES += lib/mathlib/CMSIS
+MODULES += lib/mathlib
+MODULES += lib/mathlib/math/filter
+MODULES += lib/ecl
+MODULES += lib/external_lgpl
+MODULES += lib/geo
+MODULES += lib/conversion
+MODULES += lib/launchdetection
+
+#
+# Demo apps
+#
+#MODULES += examples/math_demo
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/hello_sky
+MODULES += examples/px4_simple_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/daemon
+#MODULES += examples/px4_daemon_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/debug_values
+#MODULES += examples/px4_mavlink_debug
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control
+#MODULES += examples/fixedwing_control
+
+# Hardware test
+#MODULES += examples/hwtest
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+BUILTIN_COMMANDS := \
+ $(call _B, hello, , 2048, hello_main) \
+ $(call _B, i2c, , 2048, i2c_main)
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index b519e0e7a..808b635bb 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -48,6 +48,16 @@ NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
+# Check if the right version of the toolchain is available
+#
+CROSSDEV_VER_SUPPORTED = 4.7
+CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion)
+
+ifeq (,$(findstring $(CROSSDEV_VER_SUPPORTED),$(CROSSDEV_VER_FOUND)))
+$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of $(CROSSDEV_VER_SUPPORTED).x)
+endif
+
+
# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
MAXOPTIMIZATION ?= -O3
@@ -76,7 +86,7 @@ ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions \
ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions \
-ffixed-r10
-ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
+ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
# Pick the right set of flags for the architecture.
#
@@ -265,7 +275,7 @@ define SYM_TO_BIN
$(Q) $(OBJCOPY) -O binary $1 $2
endef
-# Take the raw binary $1 and make it into an object file $2.
+# Take the raw binary $1 and make it into an object file $2.
# The symbol $3 points to the beginning of the file, and $3_len
# gives its length.
#
diff --git a/nuttx-configs/aerocore/include/board.h b/nuttx-configs/aerocore/include/board.h
new file mode 100644
index 000000000..8705c1bc2
--- /dev/null
+++ b/nuttx-configs/aerocore/include/board.h
@@ -0,0 +1,263 @@
+/************************************************************************************
+ * configs/aerocore/include/board.h
+ * include/arch/board/board.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+
+#include <stm32.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The AeroCore uses a 24MHz crystal connected to the HSE.
+ *
+ * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
+ * 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_PPQ)
+ * 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
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * = (24,000,000 / 24) * 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)
+
+/* Alternate function pin selections ************************************************/
+
+/*
+ * UARTs.
+ */
+/* USART1 on PB[6,7]: GPS */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_2
+
+/* USART2 on PD[5,6]: J5 Breakout */
+#define GPIO_USART2_RX GPIO_USART2_RX_2
+#define GPIO_USART2_TX GPIO_USART2_TX_2
+#define GPIO_USART2_CTS 0 // unused
+#define GPIO_USART2_RTS 0 // unused
+
+/* USART3 on PD[8,9]: to DuoVero UART2 */
+#define GPIO_USART3_RX GPIO_USART3_RX_3
+#define GPIO_USART3_TX GPIO_USART3_TX_3
+#define GPIO_USART3_CTS 0 // unused
+#define GPIO_USART3_RTS 0 // unused
+
+/* UART7 on PE[78]: J7 Breakout */
+#define GPIO_UART7_RX GPIO_UART7_RX_1
+#define GPIO_UART7_TX GPIO_UART7_TX_1
+
+/*
+ * UART8 on PE[0-1]: System Console on Port C of USB (J7)
+ * No alternate pin config
+*/
+
+/* USART[1,6] require a RX DMA configuration */
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
+
+/*
+ * 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.
+ */
+
+/* PB[10-11]: I2C2 is broken out on J9 header */
+#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)
+
+/*
+ * SPI
+ */
+/* PA[4-7] SPI1 broken out on J12 */
+#define GPIO_SPI1_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) /* should be GPIO_SPI1_NSS_2 but use as a GPIO */
+#define GPIO_SPI1_SCK (GPIO_SPI1_SCK_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI1_MISO (GPIO_SPI1_MISO_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI1_MOSI (GPIO_SPI1_MOSI_1|GPIO_SPEED_50MHz)
+
+/* PB[12-15]: SPI2 connected to DuoVero SPI1 */
+#define GPIO_SPI2_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) /* should be GPIO_SPI2_NSS_2 but use as a GPIO */
+#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI2_MISO (GPIO_SPI2_MISO_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
+
+/* PC[10-12]: SPI3 connected to onboard sensors */
+#define GPIO_SPI3_SCK (GPIO_SPI3_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI3_MISO (GPIO_SPI3_MISO_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI3_MOSI (GPIO_SPI3_MOSI_2|GPIO_SPEED_50MHz)
+
+/* PE[11-14]: SPI4 connected to FRAM */
+#define GPIO_SPI4_NSS (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN11) /* should be GPIO_SPI4_NSS_2 but use as a GPIO */
+#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_2|GPIO_SPEED_50MHz)
+
+/************************************************************************************
+ * 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);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx-configs/aerocore/include/nsh_romfsimg.h b/nuttx-configs/aerocore/include/nsh_romfsimg.h
new file mode 100644
index 000000000..15e4e7a8d
--- /dev/null
+++ b/nuttx-configs/aerocore/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/aerocore/nsh/Make.defs b/nuttx-configs/aerocore/nsh/Make.defs
new file mode 100644
index 000000000..c7a1b71bb
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/Make.defs
@@ -0,0 +1,179 @@
+############################################################################
+# configs/aerocore/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/src/examples/flow_position_control/module.mk b/nuttx-configs/aerocore/nsh/appconfig
index b10dc490a..2850dac06 100644
--- a/src/examples/flow_position_control/module.mk
+++ b/nuttx-configs/aerocore/nsh/appconfig
@@ -1,6 +1,8 @@
############################################################################
+# configs/aerocore/nsh/appconfig
#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+# 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
@@ -12,7 +14,7 @@
# 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
+# 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.
#
@@ -31,11 +33,10 @@
#
############################################################################
-#
-# Build multirotor position control
-#
+# Path to example in apps/examples containing the user_start entry point
-MODULE_COMMAND = flow_position_control
+CONFIGURED_APPS += examples/nsh
-SRCS = flow_position_control_main.c \
- flow_position_control_params.c
+# The NSH application library
+CONFIGURED_APPS += nshlib
+CONFIGURED_APPS += system/readline
diff --git a/nuttx-configs/aerocore/nsh/defconfig b/nuttx-configs/aerocore/nsh/defconfig
new file mode 100644
index 000000000..8d0bae7b9
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/defconfig
@@ -0,0 +1,950 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+CONFIG_NUTTX_NEWCONFIG=y
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# 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 is not set
+
+#
+# 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_CODEREDL is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL 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 is not set
+# 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=y
+# 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_STM32F427=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 is not set
+CONFIG_STM32_I2C2=y
+# CONFIG_STM32_I2C3 is not set
+# CONFIG_STM32_OTGFS is not set
+# 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=y
+CONFIG_STM32_SPI3=y
+CONFIG_STM32_SPI4=y
+# CONFIG_STM32_SPI5 is not set
+# CONFIG_STM32_SPI6 is not set
+CONFIG_STM32_SYSCFG=y
+CONFIG_STM32_TIM1=y
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+CONFIG_STM32_TIM4=y
+CONFIG_STM32_TIM5=y
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_TIM9=y
+# CONFIG_STM32_TIM10 is not set
+# CONFIG_STM32_TIM11 is not set
+# CONFIG_STM32_TIM12 is not set
+# CONFIG_STM32_TIM13 is not set
+# CONFIG_STM32_TIM14 is not set
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=y
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USART6 is not set
+CONFIG_STM32_UART7=y
+CONFIG_STM32_UART8=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 is not set
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+CONFIG_STM32_JTAG_SW_ENABLE=y
+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_TIM1_PWM is not set
+# CONFIG_STM32_TIM3_PWM is not set
+# CONFIG_STM32_TIM4_PWM is not set
+# CONFIG_STM32_TIM5_PWM is not set
+# CONFIG_STM32_TIM9_PWM is not set
+# CONFIG_STM32_TIM1_ADC is not set
+# CONFIG_STM32_TIM3_ADC 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=y
+# CONFIG_USART2_RS485 is not set
+CONFIG_USART2_RXDMA=y
+# CONFIG_USART3_RS485 is not set
+CONFIG_USART3_RXDMA=y
+# CONFIG_UART7_RS485 is not set
+CONFIG_UART7_RXDMA=y
+# CONFIG_UART8_RS485 is not set
+CONFIG_UART8_RXDMA=y
+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=262144
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=4096
+
+#
+# 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
+
+#
+# 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=y
+# 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 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=36
+CONFIG_NFILE_STREAMS=8
+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 is not set
+CONFIG_MTD=y
+
+#
+# MTD Configuration
+#
+CONFIG_MTD_PARTITION=y
+CONFIG_MTD_BYTE_WRITE=y
+
+#
+# MTD Device Drivers
+#
+# CONFIG_RAMMTD is not set
+# CONFIG_MTD_AT24XX is not set
+# CONFIG_MTD_AT45DB is not set
+# CONFIG_MTD_M25P is not set
+# CONFIG_MTD_SMART is not set
+CONFIG_MTD_RAMTRON=y
+CONFIG_RAMTRON_FUJITSU=y
+# CONFIG_MTD_SST25 is not set
+# CONFIG_MTD_SST39FV is not set
+# CONFIG_MTD_W25 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_16550_UART is not set
+CONFIG_ARCH_HAVE_UART7=y
+CONFIG_ARCH_HAVE_UART8=y
+CONFIG_ARCH_HAVE_USART1=y
+CONFIG_ARCH_HAVE_USART2=y
+CONFIG_ARCH_HAVE_USART3=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_USART3_SERIAL_CONSOLE is not set
+# CONFIG_UART7_SERIAL_CONSOLE is not set
+CONFIG_UART8_SERIAL_CONSOLE=y
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=512
+CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_BAUD=115200
+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=115200
+CONFIG_USART2_BITS=8
+CONFIG_USART2_PARITY=0
+CONFIG_USART2_2STOP=0
+# CONFIG_USART2_IFLOWCONTROL is not set
+# CONFIG_USART2_OFLOWCONTROL is not set
+
+#
+# USART3 Configuration
+#
+CONFIG_USART3_RXBUFSIZE=512
+CONFIG_USART3_TXBUFSIZE=512
+CONFIG_USART3_BAUD=115200
+CONFIG_USART3_BITS=8
+CONFIG_USART3_PARITY=0
+CONFIG_USART3_2STOP=0
+# CONFIG_USART3_IFLOWCONTROL is not set
+# CONFIG_USART3_OFLOWCONTROL is not set
+
+#
+# UART7 Configuration
+#
+CONFIG_UART7_RXBUFSIZE=512
+CONFIG_UART7_TXBUFSIZE=512
+CONFIG_UART7_BAUD=115200
+CONFIG_UART7_BITS=8
+CONFIG_UART7_PARITY=0
+CONFIG_UART7_2STOP=0
+# CONFIG_UART7_IFLOWCONTROL is not set
+# CONFIG_UART7_OFLOWCONTROL is not set
+
+#
+# UART8 Configuration
+#
+CONFIG_UART8_RXBUFSIZE=512
+CONFIG_UART8_TXBUFSIZE=512
+CONFIG_UART8_BAUD=115200
+CONFIG_UART8_BITS=8
+CONFIG_UART8_PARITY=0
+CONFIG_UART8_2STOP=0
+# CONFIG_UART8_IFLOWCONTROL is not set
+# CONFIG_UART8_OFLOWCONTROL is not set
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+# CONFIG_USBDEV 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=y
+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 is not set
+
+#
+# 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 is not set
+# CONFIG_GRAN_INTR is not set
+
+#
+# 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=32
+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=2000
+CONFIG_SCHED_LPWORK=y
+CONFIG_SCHED_LPWORKPRIORITY=50
+CONFIG_SCHED_LPWORKPERIOD=50000
+CONFIG_SCHED_LPWORKSTACKSIZE=2000
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+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_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=y
+# 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_MTDPART is not set
+# 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
+
+#
+# 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=y
+CONFIG_I2CTOOL_MINBUS=0
+CONFIG_I2CTOOL_MAXBUS=3
+CONFIG_I2CTOOL_MINADDR=0x03
+CONFIG_I2CTOOL_MAXADDR=0x77
+CONFIG_I2CTOOL_MAXREGADDR=0xff
+CONFIG_I2CTOOL_DEFFREQ=4000000
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+# CONFIG_SYSTEM_FLASH_ERASEALL is not set
+
+#
+# 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/aerocore/nsh/setenv.sh b/nuttx-configs/aerocore/nsh/setenv.sh
new file mode 100755
index 000000000..2327f38a1
--- /dev/null
+++ b/nuttx-configs/aerocore/nsh/setenv.sh
@@ -0,0 +1,67 @@
+#!/bin/bash
+# configs/aerocore/nsh/setenv.sh
+#
+# 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.
+#
+
+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 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 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"
+
+# This 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/aerocore/scripts/ld.script b/nuttx-configs/aerocore/scripts/ld.script
new file mode 100644
index 000000000..968d3127f
--- /dev/null
+++ b/nuttx-configs/aerocore/scripts/ld.script
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * configs/aerocore/common/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 STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and
+ * 256Kb 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 SRAM beginning at address 0x2002:0000
+ * 4) 64Kb of TCM 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 = 2032K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
+ 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/aerocore/src/Makefile b/nuttx-configs/aerocore/src/Makefile
new file mode 100644
index 000000000..859ba4ab2
--- /dev/null
+++ b/nuttx-configs/aerocore/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# configs/aerocore/src/Makefile
+#
+# 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)/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/aerocore/src/empty.c b/nuttx-configs/aerocore/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx-configs/aerocore/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/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index 127418f1f..bc0c12067 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -418,7 +418,7 @@ CONFIG_PREALLOC_TIMERS=50
# Stack and heap information
#
CONFIG_IDLETHREAD_STACKSIZE=4096
-CONFIG_USERMAIN_STACKSIZE=4096
+CONFIG_USERMAIN_STACKSIZE=3500
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
#
# USART1 Configuration
#
-CONFIG_USART1_RXBUFSIZE=512
-CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART1_RXBUFSIZE=256
+CONFIG_USART1_TXBUFSIZE=128
CONFIG_USART1_BAUD=57600
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0
@@ -528,8 +528,8 @@ CONFIG_USART2_OFLOWCONTROL=y
#
# UART5 Configuration
#
-CONFIG_UART5_RXBUFSIZE=512
-CONFIG_UART5_TXBUFSIZE=512
+CONFIG_UART5_RXBUFSIZE=256
+CONFIG_UART5_TXBUFSIZE=128
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
@@ -540,8 +540,8 @@ CONFIG_UART5_2STOP=0
#
# USART6 Configuration
#
-CONFIG_USART6_RXBUFSIZE=512
-CONFIG_USART6_TXBUFSIZE=512
+CONFIG_USART6_RXBUFSIZE=128
+CONFIG_USART6_TXBUFSIZE=64
CONFIG_USART6_BAUD=57600
CONFIG_USART6_BITS=8
CONFIG_USART6_PARITY=0
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index b88f61ce8..e5bb772b3 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -119,7 +119,7 @@ int ardrone_interface_main(int argc, char *argv[])
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
- 2048,
+ 1100,
ardrone_interface_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/drivers/ardrone_interface/module.mk b/src/drivers/ardrone_interface/module.mk
index 058bd1397..d8e6c76c6 100644
--- a/src/drivers/ardrone_interface/module.mk
+++ b/src/drivers/ardrone_interface/module.mk
@@ -38,3 +38,4 @@
MODULE_COMMAND = ardrone_interface
SRCS = ardrone_interface.c \
ardrone_motor_control.c
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index b75c2297f..5c502f682 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -194,6 +194,26 @@ private:
bool systemstate_run;
+ int vehicle_status_sub_fd;
+ int vehicle_control_mode_sub_fd;
+ int vehicle_gps_position_sub_fd;
+ int actuator_armed_sub_fd;
+ int safety_sub_fd;
+
+ int num_of_cells;
+ int detected_cells_runcount;
+
+ int t_led_color[8];
+ int t_led_blink;
+ int led_thread_runcount;
+ int led_interval;
+
+ bool topic_initialized;
+ bool detected_cells_blinked;
+ bool led_thread_ready;
+
+ int num_of_used_sats;
+
void setLEDColor(int ledcolor);
static void led_trampoline(void *arg);
void led();
@@ -265,7 +285,22 @@ BlinkM::BlinkM(int bus, int blinkm) :
led_color_7(LED_OFF),
led_color_8(LED_OFF),
led_blink(LED_NOBLINK),
- systemstate_run(false)
+ systemstate_run(false),
+ vehicle_status_sub_fd(-1),
+ vehicle_control_mode_sub_fd(-1),
+ vehicle_gps_position_sub_fd(-1),
+ actuator_armed_sub_fd(-1),
+ safety_sub_fd(-1),
+ num_of_cells(0),
+ detected_cells_runcount(0),
+ t_led_color({0}),
+ t_led_blink(0),
+ led_thread_runcount(0),
+ led_interval(1000),
+ topic_initialized(false),
+ detected_cells_blinked(false),
+ led_thread_ready(true),
+ num_of_used_sats(0)
{
memset(&_work, 0, sizeof(_work));
}
@@ -382,31 +417,6 @@ void
BlinkM::led()
{
- static int vehicle_status_sub_fd;
- static int vehicle_control_mode_sub_fd;
- static int vehicle_gps_position_sub_fd;
- static int actuator_armed_sub_fd;
- static int safety_sub_fd;
-
- static int num_of_cells = 0;
- static int detected_cells_runcount = 0;
-
- static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
- static int t_led_blink = 0;
- static int led_thread_runcount=0;
- static int led_interval = 1000;
-
- static int no_data_vehicle_status = 0;
- static int no_data_vehicle_control_mode = 0;
- static int no_data_actuator_armed = 0;
- static int no_data_vehicle_gps_position = 0;
-
- static bool topic_initialized = false;
- static bool detected_cells_blinked = false;
- static bool led_thread_ready = true;
-
- int num_of_used_sats = 0;
-
if(!topic_initialized) {
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 250);
@@ -494,6 +504,11 @@ BlinkM::led()
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
+ int no_data_vehicle_status = 0;
+ int no_data_vehicle_control_mode = 0;
+ int no_data_actuator_armed = 0;
+ int no_data_vehicle_gps_position = 0;
+
if (new_data_vehicle_status) {
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
no_data_vehicle_status = 0;
@@ -638,11 +653,11 @@ BlinkM::led()
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
/* indicate main control state */
- if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
+ if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
led_color_4 = LED_GREEN;
else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
led_color_4 = LED_BLUE;
- else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
led_color_4 = LED_YELLOW;
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
led_color_4 = LED_WHITE;
diff --git a/src/drivers/boards/aerocore/aerocore_init.c b/src/drivers/boards/aerocore/aerocore_init.c
new file mode 100644
index 000000000..4e3ba2d7e
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_init.c
@@ -0,0 +1,282 @@
+/****************************************************************************
+ *
+ * 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 aerocore_init.c
+ *
+ * AeroCore-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+#include <nuttx/gran.h>
+
+#include <stm32.h>
+#include "board_config.h"
+#include <stm32_uart.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
+
+#include <systemlib/cpuload.h>
+#include <systemlib/perf_counter.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_FAT_DMAMEMORY)
+# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
+# error microSD DMA support requires CONFIG_GRAN
+# endif
+
+static GRAN_HANDLE dma_allocator;
+
+/*
+ * The DMA heap size constrains the total number of things that can be
+ * ready to do DMA at a time.
+ *
+ * For example, FAT DMA depends on one sector-sized buffer per filesystem plus
+ * one sector-sized buffer per file.
+ *
+ * We use a fundamental alignment / granule size of 64B; this is sufficient
+ * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
+ */
+static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
+static perf_counter_t g_dma_perf;
+
+static void
+dma_alloc_init(void)
+{
+ dma_allocator = gran_initialize(g_dma_heap,
+ sizeof(g_dma_heap),
+ 7, /* 128B granule - must be > alignment (XXX bug?) */
+ 6); /* 64B alignment */
+ if (dma_allocator == NULL) {
+ message("[boot] DMA allocator setup FAILED");
+ } else {
+ g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/*
+ * DMA-aware allocator stubs for the FAT filesystem.
+ */
+
+__EXPORT void *fat_dma_alloc(size_t size);
+__EXPORT void fat_dma_free(FAR void *memory, size_t size);
+
+void *
+fat_dma_alloc(size_t size)
+{
+ perf_count(g_dma_perf);
+ return gran_alloc(dma_allocator, size);
+}
+
+void
+fat_dma_free(FAR void *memory, size_t size)
+{
+ gran_free(dma_allocator, memory, size);
+}
+
+#else
+
+# define dma_alloc_init()
+
+#endif
+
+/************************************************************************************
+ * 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.
+ *
+ ************************************************************************************/
+
+__EXPORT void
+stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi3;
+static struct spi_dev_s *spi4;
+
+#include <math.h>
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
+ stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure Sensors on SPI bus #3 */
+ spi3 = up_spiinitialize(3);
+ if (!spi3) {
+ message("[boot] FAILED to initialize SPI port 3\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: 1MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi3, 10000000);
+ SPI_SETBITS(spi3, 8);
+ SPI_SETMODE(spi3, SPIDEV_MODE3);
+ SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
+ up_udelay(20);
+ message("[boot] Initialized SPI port 3 (SENSORS)\n");
+
+ /* Configure FRAM on SPI bus #4 */
+ spi4 = up_spiinitialize(4);
+ if (!spi4) {
+ message("[boot] FAILED to initialize SPI port 4\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: ~10MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
+ SPI_SETBITS(spi4, 8);
+ SPI_SETMODE(spi4, SPIDEV_MODE0);
+ SPI_SELECT(spi4, SPIDEV_FLASH, false);
+ message("[boot] Initialized SPI port 4 (FRAM)\n");
+
+ return OK;
+}
diff --git a/src/examples/flow_position_control/flow_position_control_params.h b/src/drivers/boards/aerocore/aerocore_led.c
index d0c8fc722..e40d1730c 100644
--- a/src/examples/flow_position_control/flow_position_control_params.h
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -33,68 +31,91 @@
*
****************************************************************************/
-/*
- * @file flow_position_control_params.h
- *
- * Parameters for position controller
- */
-
-#include <systemlib/param/param.h>
-
-struct flow_position_control_params {
- float pos_p;
- float pos_d;
- float height_p;
- float height_i;
- float height_d;
- float height_rate;
- float height_min;
- float height_max;
- float thrust_feedforward;
- float limit_speed_x;
- float limit_speed_y;
- float limit_height_error;
- float limit_thrust_int;
- float limit_thrust_upper;
- float limit_thrust_lower;
- float limit_yaw_step;
- float manual_threshold;
- float rc_scale_pitch;
- float rc_scale_roll;
- float rc_scale_yaw;
-};
-
-struct flow_position_control_param_handles {
- param_t pos_p;
- param_t pos_d;
- param_t height_p;
- param_t height_i;
- param_t height_d;
- param_t height_rate;
- param_t height_min;
- param_t height_max;
- param_t thrust_feedforward;
- param_t limit_speed_x;
- param_t limit_speed_y;
- param_t limit_height_error;
- param_t limit_thrust_int;
- param_t limit_thrust_upper;
- param_t limit_thrust_lower;
- param_t limit_yaw_step;
- param_t manual_threshold;
- param_t rc_scale_pitch;
- param_t rc_scale_roll;
- param_t rc_scale_yaw;
-};
-
/**
- * Initialize all parameter handles and values
+ * @file aerocore_led.c
*
+ * AeroCore LED backend.
*/
-int parameters_init(struct flow_position_control_param_handles *h);
-/**
- * Update all parameters
- *
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
*/
-int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p);
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+__EXPORT void led_init()
+{
+ stm32_configgpio(GPIO_LED0);
+ stm32_configgpio(GPIO_LED1);
+}
+
+__EXPORT void led_on(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
+
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
+
+__EXPORT void led_off(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, false);
+ break;
+
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, false);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ switch (led) {
+ case 0:
+ if (stm32_gpioread(GPIO_LED0))
+ stm32_gpiowrite(GPIO_LED0, false);
+ else
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
+
+ case 1:
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
diff --git a/src/drivers/boards/aerocore/aerocore_pwm_servo.c b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
new file mode 100644
index 000000000..251eaff7b
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * 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 aerocore_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
+ */
+
+#include <stdint.h>
+
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
+
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "board_config.h"
+
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1500,
+ }
+};
diff --git a/src/drivers/boards/aerocore/aerocore_spi.c b/src/drivers/boards/aerocore/aerocore_spi.c
new file mode 100644
index 000000000..e329bd9d1
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_spi.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ *
+ * 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 aerocore_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include <up_arch.h>
+#include <chip.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI1_NSS);
+ stm32_gpiowrite(GPIO_SPI1_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI2_NSS);
+ stm32_gpiowrite(GPIO_SPI2_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+
+ stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
+ stm32_configgpio(GPIO_EXTI_MAG_DRDY);
+ stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
+#endif
+
+#ifdef CONFIG_STM32_SPI4
+ stm32_configgpio(GPIO_SPI4_NSS);
+ stm32_gpiowrite(GPIO_SPI4_NSS, 1);
+#endif
+}
+
+#ifdef CONFIG_STM32_SPI1
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+
+#ifdef CONFIG_STM32_SPI4
+__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI4_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
new file mode 100644
index 000000000..70142a314
--- /dev/null
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -0,0 +1,176 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 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 board_config.h
+ *
+ * AeroCore internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+#define UDID_START 0x1FFF7A10
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+
+/* LEDs */
+#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
+
+/* Gyro */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
+#define SENSOR_BOARD_ROTATION_DEFAULT 3 /* SENSOR_BOARD_ROTATION_270_DEG */
+
+/* Accel & Mag */
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
+
+/* GPS */
+#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
+#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
+
+/* SPI3--Sensors */
+#define PX4_SPI_BUS_SENSORS 3
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
+
+/* Nominal chip selects for devices on SPI bus #3 */
+#define PX4_SPIDEV_ACCEL_MAG 0
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_BARO 2
+
+/* User GPIOs broken out on J11 */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
+
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* PWM
+ *
+ * Eight PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PA8 : TIM1_CH1
+ * CH2 : PA9 : TIM1_CH2
+ * CH3 : PA10 : TIM1_CH3
+ * CH4 : PA11 : TIM1_CH4
+ * CH5 : PC6 : TIM3_CH1
+ * CH6 : PC7 : TIM3_CH2
+ * CH7 : PC8 : TIM3_CH3
+ * CH8 : PC9 : TIM3_CH4
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
+#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
+#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
+#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
+#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer 8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/* Tone Alarm (no onboard speaker )*/
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/aerocore/module.mk b/src/drivers/boards/aerocore/module.mk
new file mode 100644
index 000000000..b53fe0a29
--- /dev/null
+++ b/src/drivers/boards/aerocore/module.mk
@@ -0,0 +1,8 @@
+#
+# Board-specific startup code for the AeroCore
+#
+
+SRCS = aerocore_init.c \
+ aerocore_pwm_servo.c \
+ aerocore_spi.c \
+ aerocore_led.c
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 02c26b5c0..58273f2d2 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -85,6 +85,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+#define PX4_SPI_BUS_SENSORS 1
+
/*
* Use these in place of the spi_dev_e enumeration to
* select a specific SPI device on SPI1
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 7cfca7656..c2de1bfba 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -107,6 +107,8 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
+#define PX4_SPI_BUS_SENSORS 1
+
/* 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_MAG 2
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index f60964c2b..5acd0d343 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -94,6 +94,14 @@
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+/*
+ * AeroCore GPIO numbers and configuration.
+ *
+ */
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+#endif
+
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
/* no GPIO driver on the PX4IOv1 board */
#endif
@@ -146,4 +154,4 @@
#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
-#endif /* _DRV_GPIO_H */ \ No newline at end of file
+#endif /* _DRV_GPIO_H */
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index 06e3535b3..e14f4e00d 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -43,10 +43,14 @@
#include <stdint.h>
#include <sys/ioctl.h>
+#include "board_config.h"
+
#include "drv_sensor.h"
#include "drv_orb_dev.h"
+#ifndef GPS_DEFAULT_UART_PORT
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
+#endif
#define GPS_DEVICE_PATH "/dev/gps"
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index 146a06e7c..2de7063ea 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -154,8 +154,9 @@ ETSAirspeed::collect()
return ret;
}
- uint16_t diff_pres_pa = val[1] << 8 | val[0];
- if (diff_pres_pa == 0) {
+ uint16_t diff_pres_pa_raw = val[1] << 8 | val[0];
+ uint16_t diff_pres_pa;
+ if (diff_pres_pa_raw == 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
@@ -165,10 +166,10 @@ ETSAirspeed::collect()
return -1;
}
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+ if (diff_pres_pa_raw < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
} else {
- diff_pres_pa -= _diff_pres_offset;
+ diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
}
// Track maximum differential pressure measured (so we can work out top speed).
@@ -183,6 +184,7 @@ ETSAirspeed::collect()
// XXX we may want to smooth out the readings to remove noise.
report.differential_pressure_filtered_pa = (float)diff_pres_pa;
+ report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
report.temperature = -1000.0f;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
diff --git a/src/drivers/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
index 57a03bc84..dd9b90fb3 100644
--- a/src/drivers/frsky_telemetry/frsky_data.c
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -53,6 +53,8 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_status.h>
+#include <drivers/drv_hrt.h>
+
/* FrSky sensor hub data IDs */
#define FRSKY_ID_GPS_ALT_BP 0x01
#define FRSKY_ID_TEMP1 0x02
@@ -192,17 +194,12 @@ void frsky_send_frame1(int uart)
}
/**
- * Formats the decimal latitude/longitude to the required degrees/minutes/seconds.
+ * Formats the decimal latitude/longitude to the required degrees/minutes.
*/
static float frsky_format_gps(float dec)
{
- float dms_deg = (int) dec;
- float dec_deg = dec - dms_deg;
- float dms_min = (int) (dec_deg * 60);
- float dec_min = (dec_deg * 60) - dms_min;
- float dms_sec = dec_min * 60;
-
- return (dms_deg * 100.0f) + dms_min + (dms_sec / 100.0f);
+ float dm_deg = (int) dec;
+ return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
}
/**
@@ -230,9 +227,9 @@ void frsky_send_frame2(int uart)
struct tm *tm_gps = gmtime(&time_gps);
course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
- lat = frsky_format_gps(abs(global_pos.lat));
+ lat = frsky_format_gps(fabsf(global_pos.lat));
lat_ns = (global_pos.lat < 0) ? 'S' : 'N';
- lon = frsky_format_gps(abs(global_pos.lon));
+ lon = frsky_format_gps(fabsf(global_pos.lon));
lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e)
* 25.0f / 46.0f;
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index 7b08ca69e..6e0839043 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -222,7 +222,7 @@ int frsky_telemetry_main(int argc, char *argv[])
frsky_task = task_spawn_cmd("frsky_telemetry",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 2000,
frsky_telemetry_thread_main,
(const char **)argv);
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
index 1632c74f7..9a49589ee 100644
--- a/src/drivers/frsky_telemetry/module.mk
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = frsky_telemetry
SRCS = frsky_data.c \
frsky_telemetry.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 7f65e37b1..8560716e9 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 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
@@ -56,6 +56,7 @@
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/i2c.h>
+#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
#include <systemlib/scheduling_priorities.h>
#include <systemlib/err.h>
@@ -63,6 +64,8 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <board_config.h>
+
#include "ubx.h"
#include "mtk.h"
@@ -76,12 +79,6 @@
#endif
static const int ERROR = -1;
-#ifndef CONFIG_SCHED_WORKQUEUE
-# error This requires CONFIG_SCHED_WORKQUEUE.
-#endif
-
-
-
class GPS : public device::CDev
{
public:
@@ -209,7 +206,8 @@ GPS::init()
goto out;
/* start the GPS driver worker task */
- _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("gps", SCHED_DEFAULT,
+ SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
@@ -421,7 +419,14 @@ GPS::task_main()
void
GPS::cmd_reset()
{
- //XXX add reset?
+#ifdef GPIO_GPS_NRESET
+ warnx("Toggling GPS reset pin");
+ stm32_configgpio(GPIO_GPS_NRESET);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 0);
+ usleep(100);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 1);
+ warnx("Toggled GPS reset pin");
+#endif
}
void
@@ -443,10 +448,10 @@ GPS::print_info()
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, satellites: %d, last update: %fms ago", (int)_report.fix_type,
- _report.satellites_visible, (hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
+ warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type,
+ _report.satellites_visible, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
- warnx("eph: %.2fm, epv: %.2fm", _report.eph, _report.epv);
+ warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph, (double)_report.epv);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index 2360ff39b..3b92f1bf4 100644
--- a/src/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
@@ -56,7 +56,7 @@ GPS_Helper::get_velocity_update_rate()
return _rate_vel;
}
-float
+void
GPS_Helper::reset_update_rates()
{
_rate_count_vel = 0;
@@ -64,7 +64,7 @@ GPS_Helper::reset_update_rates()
_interval_rate_start = hrt_absolute_time();
}
-float
+void
GPS_Helper::store_update_rates()
{
_rate_vel = _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f);
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index cfb9e0d43..d14a95afe 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -46,13 +46,17 @@
class GPS_Helper
{
public:
+
+ GPS_Helper() {};
+ virtual ~GPS_Helper() {};
+
virtual int configure(unsigned &baud) = 0;
virtual int receive(unsigned timeout) = 0;
int set_baudrate(const int &fd, unsigned baud);
float get_position_update_rate();
float get_velocity_update_rate();
- float reset_update_rates();
- float store_update_rates();
+ void reset_update_rates();
+ void store_update_rates();
protected:
uint8_t _rate_count_lat_lon;
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index 82c67d40a..eb382c4b2 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -41,3 +41,5 @@ SRCS = gps.cpp \
gps_helper.cpp \
mtk.cpp \
ubx.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index 99f88fb8a..ea4e95fb2 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -249,12 +249,18 @@ MTK::handle_message(gps_mtk_packet_t &packet)
warnx("mtk: unknown revision");
_gps_position->lat = 0;
_gps_position->lon = 0;
+
+ // Indicate this data is not usable and bail out
+ _gps_position->eph_m = 1000.0f;
+ _gps_position->epv_m = 1000.0f;
+ _gps_position->fix_type = 0;
+ return;
}
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
- _gps_position->eph = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
- _gps_position->epv = 0.0; //unknown in mtk custom mode
+ _gps_position->eph = packet.hdop / 100.0f; // from cm to m
+ _gps_position->epv = _gps_position->eph; // unknown in mtk custom mode, so we cheat with eph
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
_gps_position->satellites_visible = packet.satellites;
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index 95965b60d..183b81ea9 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -164,7 +164,7 @@ UBX::configure(unsigned &baudrate)
send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: configuration failed: RATE");
+ warnx("CFG FAIL: RATE");
return 1;
}
@@ -185,7 +185,7 @@ UBX::configure(unsigned &baudrate)
send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: configuration failed: NAV5");
+ warnx("CFG FAIL: NAV5");
return 1;
}
@@ -194,35 +194,42 @@ UBX::configure(unsigned &baudrate)
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV POSLLH");
+ warnx("MSG CFG FAIL: NAV POSLLH");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV TIMEUTC");
+ warnx("MSG CFG FAIL: NAV TIMEUTC");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SOL");
+ warnx("MSG CFG FAIL: NAV SOL");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV VELNED");
+ warnx("MSG CFG FAIL: NAV VELNED");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SVINFO");
+ warnx("MSG CFG FAIL: NAV SVINFO");
+ return 1;
+ }
+
+ configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("MSG CFG FAIL: MON HW");
return 1;
}
@@ -274,7 +281,7 @@ UBX::receive(unsigned timeout)
if (ret < 0) {
/* something went wrong when polling */
- warnx("ubx: poll error");
+ warnx("poll error");
return -1;
} else if (ret == 0) {
@@ -310,7 +317,7 @@ UBX::receive(unsigned timeout)
/* abort after timeout if no useful packets received */
if (time_started + timeout * 1000 < hrt_absolute_time()) {
- warnx("ubx: timeout - no useful messages");
+ warnx("timeout - no useful messages");
return -1;
}
}
@@ -383,7 +390,7 @@ UBX::parse_char(uint8_t b)
return 1; // message received successfully
} else {
- warnx("ubx: checksum wrong");
+ warnx("checksum wrong");
decode_init();
return -1;
}
@@ -392,7 +399,7 @@ UBX::parse_char(uint8_t b)
_rx_count++;
} else {
- warnx("ubx: buffer full");
+ warnx("buffer full");
decode_init();
return -1;
}
@@ -566,6 +573,24 @@ UBX::handle_message()
break;
}
+ case UBX_CLASS_MON: {
+ switch (_message_id) {
+ case UBX_MESSAGE_MON_HW: {
+
+ struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer;
+
+ _gps_position->noise_per_ms = p->noisePerMS;
+ _gps_position->jamming_indicator = p->jamInd;
+
+ ret = 1;
+ break;
+ }
+
+ default:
+ break;
+ }
+ }
+
default:
break;
}
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 79a904f4a..5cf47b60b 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -56,6 +56,7 @@
//#define UBX_CLASS_RXM 0x02
#define UBX_CLASS_ACK 0x05
#define UBX_CLASS_CFG 0x06
+#define UBX_CLASS_MON 0x0A
/* MessageIDs (the ones that are used) */
#define UBX_MESSAGE_NAV_POSLLH 0x02
@@ -72,6 +73,8 @@
#define UBX_MESSAGE_CFG_RATE 0x08
#define UBX_MESSAGE_CFG_NAV5 0x24
+#define UBX_MESSAGE_MON_HW 0x09
+
#define UBX_CFG_PRT_LENGTH 20
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
@@ -210,6 +213,27 @@ typedef struct {
uint8_t ck_b;
} gps_bin_nav_velned_packet_t;
+struct gps_bin_mon_hw_packet {
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t __reserved1;
+ uint32_t usedMask;
+ uint8_t VP[25];
+ uint8_t jamInd;
+ uint16_t __reserved3;
+ uint32_t pinIrq;
+ uint32_t pulLH;
+ uint32_t pullL;
+};
+
+
//typedef struct {
// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
// int16_t week; /**< Measurement GPS week number */
@@ -319,7 +343,7 @@ typedef enum {
//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
#pragma pack(pop)
-#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer
+#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer
class UBX : public GPS_Helper
{
@@ -383,7 +407,7 @@ private:
uint8_t _message_class;
uint8_t _message_id;
unsigned _payload_size;
- uint8_t _disable_cmd_last;
+ hrt_abstime _disable_cmd_last;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 0a047f38f..55cc077fb 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -122,7 +122,7 @@ private:
actuator_controls_s _controls;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index cdc9d3106..fddba806e 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -158,6 +158,7 @@ private:
int _class_instance;
orb_advert_t _mag_topic;
+ orb_advert_t _subsystem_pub;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
@@ -324,7 +325,9 @@ HMC5883::HMC5883(int bus) :
_reports(nullptr),
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
+ _collect_phase(false),
_mag_topic(-1),
+ _subsystem_pub(-1),
_class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
@@ -1137,13 +1140,12 @@ int HMC5883::check_calibration()
true,
_calibrated,
SUBSYSTEM_TYPE_MAG};
- static orb_advert_t pub = -1;
if (!(_pub_blocked)) {
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
+ if (_subsystem_pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), _subsystem_pub, &info);
} else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ _subsystem_pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
}
}
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 90a744015..1e779e8dc 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -51,6 +51,8 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <drivers/drv_hrt.h>
+
/* The board is very roughly 5 deg warmer than the surrounding air */
#define BOARD_TEMP_OFFSET_DEG 5
@@ -62,7 +64,6 @@ static int _airspeed_sub = -1;
static int _esc_sub = -1;
static orb_advert_t _esc_pub;
-struct esc_status_s _esc;
static bool _home_position_set = false;
static double _home_lat = 0.0d;
@@ -82,8 +83,6 @@ init_sub_messages(void)
void
init_pub_messages(void)
{
- memset(&_esc, 0, sizeof(_esc));
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
}
void
@@ -106,23 +105,26 @@ publish_gam_message(const uint8_t *buffer)
size_t size = sizeof(msg);
memset(&msg, 0, size);
memcpy(&msg, buffer, size);
+ struct esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+
+ // Publish it.
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = 1;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
+
+ esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
+ esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
+ esc.esc[0].esc_temperature = msg.temperature1 - 20;
+ esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
+ esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
/* announce the esc if needed, just publish else */
if (_esc_pub > 0) {
- orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
+ orb_publish(ORB_ID(esc_status), _esc_pub, &esc);
} else {
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
+ _esc_pub = orb_advertise(ORB_ID(esc_status), &esc);
}
-
- // Publish it.
- _esc.esc_count = 1;
- _esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
-
- _esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
- _esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
- _esc.esc[0].esc_temperature = msg.temperature1 - 20;
- _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
- _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
}
void
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 90c3db9ae..37e72388b 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -34,6 +34,9 @@
/**
* @file l3gd20.cpp
* Driver for the ST L3GD20 MEMS gyro connected via SPI.
+ *
+ * Note: With the exception of the self-test feature, the ST L3G4200D is
+ * also supported by this driver.
*/
#include <nuttx/config.h>
@@ -89,9 +92,11 @@ static const int ERROR = -1;
#define ADDR_WHO_AM_I 0x0F
#define WHO_I_AM_H 0xD7
#define WHO_I_AM 0xD4
+#define WHO_I_AM_L3G4200D 0xD3 /* for L3G4200D */
#define ADDR_CTRL_REG1 0x20
#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
+
/* keep lowpass low to avoid noise issues */
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
@@ -166,9 +171,14 @@ static const int ERROR = -1;
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
#define L3GD20_DEFAULT_RATE 760
+#define L3G4200D_DEFAULT_RATE 800
#define L3GD20_DEFAULT_RANGE_DPS 2000
#define L3GD20_DEFAULT_FILTER_FREQ 30
+#ifndef SENSOR_BOARD_ROTATION_DEFAULT
+#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
+#endif
+
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -216,6 +226,9 @@ private:
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
+ /* true if an L3G4200D is detected */
+ bool _is_l3g4200d;
+
/**
* Start automatic measurement.
*/
@@ -324,14 +337,15 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_topic(-1),
_class_instance(-1),
_current_rate(0),
- _orientation(SENSOR_BOARD_ROTATION_270_DEG),
+ _orientation(SENSOR_BOARD_ROTATION_DEFAULT),
_read(0),
_sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
_reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
_errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
- _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ)
+ _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
+ _is_l3g4200d(false)
{
// enable debug() calls
_debug_enabled = true;
@@ -413,14 +427,7 @@ L3GD20::probe()
/* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
- #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #elif CONFIG_ARCH_BOARD_PX4FMU_V2
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #else
- #error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
- #endif
-
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
success = true;
}
@@ -430,6 +437,13 @@ L3GD20::probe()
success = true;
}
+ /* Detect the L3G4200D used on AeroCore */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_L3G4200D) {
+ _is_l3g4200d = true;
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
+ success = true;
+ }
+
if (success)
return OK;
@@ -502,6 +516,9 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
+ if (_is_l3g4200d) {
+ return ioctl(filp, SENSORIOCSPOLLRATE, L3G4200D_DEFAULT_RATE);
+ }
return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
@@ -683,23 +700,26 @@ L3GD20::set_samplerate(unsigned frequency)
uint8_t bits = REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
if (frequency == 0)
- frequency = 760;
+ frequency = _is_l3g4200d ? 800 : 760;
- /* use limits good for H or non-H models */
+ /*
+ * Use limits good for H or non-H models. Rates are slightly different
+ * for L3G4200D part but register settings are the same.
+ */
if (frequency <= 100) {
- _current_rate = 95;
+ _current_rate = _is_l3g4200d ? 100 : 95;
bits |= RATE_95HZ_LP_25HZ;
} else if (frequency <= 200) {
- _current_rate = 190;
+ _current_rate = _is_l3g4200d ? 200 : 190;
bits |= RATE_190HZ_LP_50HZ;
} else if (frequency <= 400) {
- _current_rate = 380;
+ _current_rate = _is_l3g4200d ? 400 : 380;
bits |= RATE_380HZ_LP_50HZ;
} else if (frequency <= 800) {
- _current_rate = 760;
+ _current_rate = _is_l3g4200d ? 800 : 760;
bits |= RATE_760HZ_LP_50HZ;
} else {
return -EINVAL;
@@ -772,7 +792,7 @@ L3GD20::reset()
* callback fast enough to not miss data. */
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
- set_samplerate(0); // 760Hz
+ set_samplerate(0); // 760Hz or 800Hz
set_range(L3GD20_DEFAULT_RANGE_DPS);
set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
@@ -971,7 +991,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
if (g_dev == nullptr)
goto fail;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 4dee7649b..4ca8b5e42 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1793,7 +1793,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 3cb9abc49..5954c40da 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -92,8 +92,20 @@
#define MOTOR_SPINUP_COUNTER 30
#define ESC_UORB_PUBLISH_DELAY 500000
-
-
+struct MotorData_t {
+ unsigned int Version; // the version of the BL (0 = old)
+ unsigned int SetPoint; // written by attitude controller
+ unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
+ unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
+ unsigned int ReadMode; // select data to read
+ unsigned short RawPwmValue; // length of PWM pulse
+ // the following bytes must be exactly in that order!
+ unsigned int Current; // in 0.1 A steps, read back from BL
+ unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
+ unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
+ unsigned int RoundCount;
+};
class MK : public device::I2C
{
@@ -154,8 +166,10 @@ private:
actuator_controls_s _controls;
+ MotorData_t Motor[MAX_MOTORS];
+
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
@@ -195,24 +209,6 @@ const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0};
int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0};
-struct MotorData_t {
- unsigned int Version; // the version of the BL (0 = old)
- unsigned int SetPoint; // written by attitude controller
- unsigned int SetPointLowerBits; // for higher Resolution of new BLs
- float SetPoint_PX4; // Values from PX4
- unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
- unsigned int ReadMode; // select data to read
- unsigned short RawPwmValue; // length of PWM pulse
- // the following bytes must be exactly in that order!
- unsigned int Current; // in 0.1 A steps, read back from BL
- unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
- unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
- unsigned int RoundCount;
-};
-
-MotorData_t Motor[MAX_MOTORS];
-
-
namespace
{
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index ac75682c4..321fdd173 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1380,7 +1380,6 @@ MPU6000_gyro::init()
_gyro_class_instance = register_class_devname(GYRO_DEVICE_PATH);
-out:
return ret;
}
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 3fe1b0abc..1ce93aeea 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -753,8 +753,8 @@ MS5611::print_info()
printf("TEMP: %d\n", _TEMP);
printf("SENS: %lld\n", _SENS);
printf("OFF: %lld\n", _OFF);
- printf("P: %.3f\n", _P);
- printf("T: %.3f\n", _T);
+ printf("P: %.3f\n", (double)_P);
+ printf("T: %.3f\n", (double)_T);
printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
printf("factory_setup %u\n", _prom.factory_setup);
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 26216e840..8759d16a1 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -117,7 +117,7 @@ private:
device::Device *
MS5611_spi_interface(ms5611::prom_u &prom_buf)
{
- return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
}
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index e81902494..8a4bfa18c 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -92,6 +92,7 @@ public:
MODE_2PWM,
MODE_4PWM,
MODE_6PWM,
+ MODE_8PWM,
};
PX4FMU();
virtual ~PX4FMU();
@@ -113,6 +114,9 @@ private:
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
static const unsigned _max_actuators = 6;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ static const unsigned _max_actuators = 8;
+#endif
Mode _mode;
unsigned _pwm_default_rate;
@@ -149,7 +153,7 @@ private:
unsigned _num_disarmed_set;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
@@ -203,6 +207,20 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
{GPIO_VDD_5V_HIPOWER_OC, 0, 0},
{GPIO_VDD_5V_PERIPH_OC, 0, 0},
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ /* AeroCore breaks out User GPIOs on J11 */
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
+ {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0},
+ {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0},
+ {GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0},
+ {GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0},
+ {GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0},
+ {GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0},
+#endif
};
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
@@ -382,6 +400,20 @@ PX4FMU::set_mode(Mode mode)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM: // AeroCore PWMs as 8 PWM outs
+ debug("MODE_8PWM");
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0xff);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+ break;
+#endif
+
case MODE_NONE:
debug("MODE_NONE");
@@ -559,13 +591,12 @@ PX4FMU::task_main()
}
/* sleep waiting for data, stopping to check for PPM
- * input at 100Hz */
+ * input at 50Hz */
int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS);
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
- usleep(1000000);
continue;
} else if (ret == 0) {
@@ -603,6 +634,9 @@ PX4FMU::task_main()
num_outputs = 6;
break;
+ case MODE_8PWM:
+ num_outputs = 8;
+ break;
default:
num_outputs = 0;
break;
@@ -614,11 +648,9 @@ PX4FMU::task_main()
/* iterate actuators */
for (unsigned i = 0; i < num_outputs; i++) {
- /* last resort: catch NaN, INF and out-of-band errors */
- if (i >= outputs.noutputs ||
- !isfinite(outputs.output[i]) ||
- outputs.output[i] < -1.0f ||
- outputs.output[i] > 1.0f) {
+ /* last resort: catch NaN and INF */
+ if ((i >= outputs.noutputs) ||
+ !isfinite(outputs.output[i])) {
/*
* Value is NaN, INF or out of band - set to the minimum value.
* This will be clearly visible on the servo status and will limit the risk of accidentally
@@ -630,6 +662,7 @@ PX4FMU::task_main()
uint16_t pwm_limited[num_outputs];
+ /* the PWM limit call takes care of out of band errors and constrains */
pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
/* output to the servos */
@@ -758,6 +791,9 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
case MODE_2PWM:
case MODE_4PWM:
case MODE_6PWM:
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+#endif
ret = pwm_ioctl(filp, cmd, arg);
break;
@@ -987,6 +1023,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_SET(7):
+ case PWM_SERVO_SET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_SET(5):
case PWM_SERVO_SET(4):
if (_mode < MODE_6PWM) {
@@ -1014,6 +1059,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET(7):
+ case PWM_SERVO_GET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_GET(5):
case PWM_SERVO_GET(4):
if (_mode < MODE_6PWM) {
@@ -1041,12 +1095,22 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET_RATEGROUP(3):
case PWM_SERVO_GET_RATEGROUP(4):
case PWM_SERVO_GET_RATEGROUP(5):
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET_RATEGROUP(6):
+ case PWM_SERVO_GET_RATEGROUP(7):
+#endif
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
break;
case PWM_SERVO_GET_COUNT:
case MIXERIOCGETOUTPUTCOUNT:
switch (_mode) {
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+ *(unsigned *)arg = 8;
+ break;
+#endif
+
case MODE_6PWM:
*(unsigned *)arg = 6;
break;
@@ -1092,6 +1156,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
set_mode(MODE_6PWM);
break;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ case 8:
+ set_mode(MODE_8PWM);
+ break;
+#endif
default:
ret = -EINVAL;
@@ -1182,10 +1251,17 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
unsigned count = len / 2;
uint16_t values[6];
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ if (count > 8) {
+ // we have at most 8 outputs
+ count = 8;
+ }
+#else
if (count > 6) {
// we have at most 6 outputs
count = 6;
}
+#endif
// allow for misaligned values
memcpy(values, buffer, count * 2);
@@ -1460,6 +1536,9 @@ fmu_new_mode(PortMode new_mode)
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
servo_mode = PX4FMU::MODE_6PWM;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ servo_mode = PX4FMU::MODE_8PWM;
+#endif
break;
/* mixed modes supported on v1 board only */
@@ -1777,7 +1856,7 @@ fmu_main(int argc, char *argv[])
fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
-#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_AEROCORE)
fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
#endif
exit(1);
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index 05bc7a5b3..eeb59e1a1 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = fmu
SRCS = fmu.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index 2054faa12..c14f1f783 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -44,3 +44,5 @@ SRCS = px4io.cpp \
# XXX prune to just get UART registers
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index aec6dd3b7..972f45148 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -529,6 +529,11 @@ PX4IO::~PX4IO()
if (_interface != nullptr)
delete _interface;
+ /* deallocate perfs */
+ perf_free(_perf_update);
+ perf_free(_perf_write);
+ perf_free(_perf_chan_count);
+
g_dev = nullptr;
}
@@ -576,8 +581,10 @@ PX4IO::init()
ASSERT(_task == -1);
sys_restart_param = param_find("SYS_RESTART_TYPE");
- /* Indicate restart type is unknown */
- param_set(sys_restart_param, &sys_restart_val);
+ if (sys_restart_param != PARAM_INVALID) {
+ /* Indicate restart type is unknown */
+ param_set(sys_restart_param, &sys_restart_val);
+ }
/* do regular cdev init */
ret = CDev::init();
@@ -789,7 +796,12 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("px4io",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_ACTUATOR_OUTPUTS,
+ 2000,
+ (main_t)&PX4IO::task_main_trampoline,
+ nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -984,13 +996,17 @@ PX4IO::task_main()
int32_t failsafe_param_val;
param_t failsafe_param = param_find("RC_FAILS_THR");
- if (failsafe_param > 0) {
+ if (failsafe_param != PARAM_INVALID) {
param_get(failsafe_param, &failsafe_param_val);
- uint16_t failsafe_thr = failsafe_param_val;
- pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
- if (pret != OK) {
- log("failsafe upload failed");
+
+ if (failsafe_param_val > 0) {
+
+ uint16_t failsafe_thr = failsafe_param_val;
+ pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
+ if (pret != OK) {
+ log("failsafe upload failed, FS: %d us", (int)failsafe_thr);
+ }
}
}
@@ -1448,7 +1464,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
- static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
+ const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
/*
@@ -1456,8 +1472,6 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*
* This should be the common case (9 channel R/C control being a reasonable upper bound).
*/
- input_rc.timestamp_publication = hrt_absolute_time();
-
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, &regs[0], prolog + 9);
if (ret != OK)
@@ -1469,23 +1483,38 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*/
channel_count = regs[PX4IO_P_RAW_RC_COUNT];
- if (channel_count != _rc_chan_count)
+ /* limit the channel count */
+ if (channel_count > RC_INPUT_MAX_CHANNELS) {
+ channel_count = RC_INPUT_MAX_CHANNELS;
+ }
+
+ /* count channel count changes to identify signal integrity issues */
+ if (channel_count != _rc_chan_count) {
perf_count(_perf_chan_count);
+ }
_rc_chan_count = channel_count;
+ input_rc.timestamp_publication = hrt_absolute_time();
+
input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA];
input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI];
input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK);
input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT];
input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT];
+ input_rc.channel_count = channel_count;
/* rc_lost has to be set before the call to this function */
- if (!input_rc.rc_lost && !input_rc.rc_failsafe)
+ if (!input_rc.rc_lost && !input_rc.rc_failsafe) {
_rc_last_valid = input_rc.timestamp_publication;
+ }
input_rc.timestamp_last_signal = _rc_last_valid;
+ /* FIELDS NOT SET HERE */
+ /* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */
+
if (channel_count > 9) {
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, &regs[prolog + 9], channel_count - 9);
@@ -1493,8 +1522,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
return ret;
}
- input_rc.channel_count = channel_count;
- memcpy(input_rc.values, &regs[prolog], channel_count * 2);
+ /* last thing set are the actual channel values as 16 bit values */
+ for (unsigned i = 0; i < channel_count; i++) {
+ input_rc.values[i] = regs[prolog + i];
+ }
return ret;
}
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 43318ca84..3b210ac59 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -639,7 +639,7 @@ PX4IO_serial::_do_interrupt()
if (_rx_dma_status == _dma_status_waiting) {
/* verify that the received packet is complete */
- unsigned length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ int length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
perf_count(_pc_badidle);
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index a0cf98340..9109af14f 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -254,9 +254,6 @@ SF0X::~SF0X()
int
SF0X::init()
{
- int ret = ERROR;
- unsigned i = 0;
-
/* do regular cdev init */
if (CDev::init() != OK) {
goto out;
@@ -594,7 +591,7 @@ SF0X::collect()
valid = false;
/* wipe out partially read content from last cycle(s), check for dot */
- for (int i = 0; i < (lend - 2); i++) {
+ for (unsigned i = 0; i < (lend - 2); i++) {
if (_linebuf[i] == '\n') {
char buf[sizeof(_linebuf)];
memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
@@ -795,7 +792,7 @@ const int ERROR = -1;
SF0X *g_dev;
-void start();
+void start(const char *port);
void stop();
void test();
void reset();
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 3a60d2cae..aa0dca60c 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -145,7 +145,7 @@ private:
ADC::ADC(uint32_t channels) :
CDev("adc", ADC_DEVICE_PATH),
- _sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
+ _sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
_channel_count(0),
_samples(nullptr),
_to_system_power(0)
@@ -419,6 +419,10 @@ adc_main(int argc, char *argv[])
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ /* XXX this hardcodes the default channel set for AeroCore - should be configurable */
+ g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index b7c9b89a4..281f918d7 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -94,7 +94,7 @@
#elif HRT_TIMER == 3
# define HRT_TIMER_BASE STM32_TIM3_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
-# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
+# define HRT_TIMER_POWER_BIT RCC_APB1ENR_TIM3EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
# if CONFIG_STM32_TIM3
@@ -141,7 +141,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
-# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM10_CLKIN
# if CONFIG_STM32_TIM10
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
# endif
@@ -150,7 +150,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
-# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM11_CLKIN
# if CONFIG_STM32_TIM11
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
@@ -354,6 +354,9 @@ __EXPORT uint16_t ppm_frame_length = 0;
__EXPORT unsigned ppm_decoded_channels = 0;
__EXPORT uint64_t ppm_last_valid_decode = 0;
+#define PPM_DEBUG 0
+
+#if PPM_DEBUG
/* PPM edge history */
__EXPORT uint16_t ppm_edge_history[32];
unsigned ppm_edge_next;
@@ -361,6 +364,7 @@ unsigned ppm_edge_next;
/* PPM pulse history */
__EXPORT uint16_t ppm_pulse_history[32];
unsigned ppm_pulse_next;
+#endif
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
@@ -455,10 +459,12 @@ hrt_ppm_decode(uint32_t status)
/* how long since the last edge? - this handles counter wrapping implicitely. */
width = count - ppm.last_edge;
+#if PPM_DEBUG
ppm_edge_history[ppm_edge_next++] = width;
if (ppm_edge_next >= 32)
ppm_edge_next = 0;
+#endif
/*
* if this looks like a start pulse, then push the last set of values
@@ -546,10 +552,12 @@ hrt_ppm_decode(uint32_t status)
interval = count - ppm.last_mark;
ppm.last_mark = count;
+#if PPM_DEBUG
ppm_pulse_history[ppm_pulse_next++] = interval;
if (ppm_pulse_next >= 32)
ppm_pulse_next = 0;
+#endif
/* if the mark-mark timing is out of bounds, abandon the frame */
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk
index d2c48934f..a2a9eb113 100644
--- a/src/examples/fixedwing_control/module.mk
+++ b/src/examples/fixedwing_control/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control
SRCS = main.c \
params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/examples/flow_position_control/flow_position_control_main.c b/src/examples/flow_position_control/flow_position_control_main.c
deleted file mode 100644
index 391e40ac1..000000000
--- a/src/examples/flow_position_control/flow_position_control_main.c
+++ /dev/null
@@ -1,613 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * 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 flow_position_control.c
- *
- * Optical flow position controller
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdbool.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <debug.h>
-#include <termios.h>
-#include <time.h>
-#include <math.h>
-#include <sys/prctl.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/actuator_armed.h>
-#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
-#include <uORB/topics/filtered_bottom_flow.h>
-#include <systemlib/systemlib.h>
-#include <systemlib/perf_counter.h>
-#include <systemlib/err.h>
-#include <poll.h>
-#include <mavlink/mavlink_log.h>
-
-#include "flow_position_control_params.h"
-
-
-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 */
-
-__EXPORT int flow_position_control_main(int argc, char *argv[]);
-
-/**
- * Mainloop of position controller.
- */
-static int flow_position_control_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: deamon {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_spawn_cmd().
- */
-int flow_position_control_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start"))
- {
- if (thread_running)
- {
- printf("flow position control already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn_cmd("flow_position_control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 6,
- 4096,
- flow_position_control_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)
- printf("\tflow position control app is running\n");
- else
- printf("\tflow position control app not started\n");
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-static int
-flow_position_control_thread_main(int argc, char *argv[])
-{
- /* welcome user */
- thread_running = true;
- static int mavlink_fd;
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
- mavlink_log_info(mavlink_fd, "[fpc] started");
-
- uint32_t counter = 0;
- const float time_scale = powf(10.0f,-6.0f);
-
- /* structures */
- struct actuator_armed_s armed;
- memset(&armed, 0, sizeof(armed));
- struct vehicle_control_mode_s control_mode;
- memset(&control_mode, 0, sizeof(control_mode));
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- struct manual_control_setpoint_s manual;
- memset(&manual, 0, sizeof(manual));
- struct filtered_bottom_flow_s filtered_flow;
- memset(&filtered_flow, 0, sizeof(filtered_flow));
- struct vehicle_local_position_s local_pos;
- memset(&local_pos, 0, sizeof(local_pos));
- struct vehicle_bodyframe_speed_setpoint_s speed_sp;
- memset(&speed_sp, 0, sizeof(speed_sp));
-
- /* subscribe to attitude, motor setpoints and system state */
- int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
- int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
- int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
- int vehicle_local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
-
- orb_advert_t speed_sp_pub;
- bool speed_setpoint_adverted = false;
-
- /* parameters init*/
- struct flow_position_control_params params;
- struct flow_position_control_param_handles param_handles;
- parameters_init(&param_handles);
- parameters_update(&param_handles, &params);
-
- /* init flow sum setpoint */
- float flow_sp_sumx = 0.0f;
- float flow_sp_sumy = 0.0f;
-
- /* init yaw setpoint */
- float yaw_sp = 0.0f;
-
- /* init height setpoint */
- float height_sp = params.height_min;
-
- /* height controller states */
- bool start_phase = true;
- bool landing_initialized = false;
- float landing_thrust_start = 0.0f;
-
- /* states */
- float integrated_h_error = 0.0f;
- float last_local_pos_z = 0.0f;
- bool update_flow_sp_sumx = false;
- bool update_flow_sp_sumy = false;
- uint64_t last_time = 0.0f;
- float dt = 0.0f; // s
-
-
- /* register the perf counter */
- perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "flow_position_control_runtime");
- perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "flow_position_control_interval");
- perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "flow_position_control_err");
-
- static bool sensors_ready = false;
- static bool status_changed = false;
-
- while (!thread_should_exit)
- {
- /* wait for first attitude msg to be sure all data are available */
- if (sensors_ready)
- {
- /* polling */
- struct pollfd fds[2] = {
- { .fd = filtered_bottom_flow_sub, .events = POLLIN }, // positions from estimator
- { .fd = parameter_update_sub, .events = POLLIN }
-
- };
-
- /* wait for a position update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
-
- if (ret < 0)
- {
- /* poll error, count it in perf */
- perf_count(mc_err_perf);
- }
- else if (ret == 0)
- {
- /* no return value, ignore */
-// printf("[flow position control] no filtered flow updates\n");
- }
- else
- {
- /* parameter update available? */
- if (fds[1].revents & POLLIN)
- {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
-
- parameters_update(&param_handles, &params);
- mavlink_log_info(mavlink_fd,"[fpc] parameters updated.");
- }
-
- /* only run controller if position/speed changed */
- if (fds[0].revents & POLLIN)
- {
- perf_begin(mc_loop_perf);
-
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- /* get a local copy of filtered bottom flow */
- orb_copy(ORB_ID(filtered_bottom_flow), filtered_bottom_flow_sub, &filtered_flow);
- /* get a local copy of local position */
- orb_copy(ORB_ID(vehicle_local_position), vehicle_local_position_sub, &local_pos);
- /* get a local copy of control mode */
- orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
-
- if (control_mode.flag_control_velocity_enabled)
- {
- float manual_pitch = manual.pitch / params.rc_scale_pitch; // 0 to 1
- float manual_roll = manual.roll / params.rc_scale_roll; // 0 to 1
- float manual_yaw = manual.yaw / params.rc_scale_yaw; // -1 to 1
-
- if(status_changed == false)
- mavlink_log_info(mavlink_fd,"[fpc] flow POSITION control engaged");
-
- status_changed = true;
-
- /* calc dt */
- if(last_time == 0)
- {
- last_time = hrt_absolute_time();
- continue;
- }
- dt = ((float) (hrt_absolute_time() - last_time)) * time_scale;
- last_time = hrt_absolute_time();
-
- /* update flow sum setpoint */
- if (update_flow_sp_sumx)
- {
- flow_sp_sumx = filtered_flow.sumx;
- update_flow_sp_sumx = false;
- }
- if (update_flow_sp_sumy)
- {
- flow_sp_sumy = filtered_flow.sumy;
- update_flow_sp_sumy = false;
- }
-
- /* calc new bodyframe speed setpoints */
- float speed_body_x = (flow_sp_sumx - filtered_flow.sumx) * params.pos_p - filtered_flow.vx * params.pos_d;
- float speed_body_y = (flow_sp_sumy - filtered_flow.sumy) * params.pos_p - filtered_flow.vy * params.pos_d;
- float speed_limit_height_factor = height_sp; // the settings are for 1 meter
-
- /* overwrite with rc input if there is any */
- if(isfinite(manual_pitch) && isfinite(manual_roll))
- {
- if(fabsf(manual_pitch) > params.manual_threshold)
- {
- speed_body_x = -manual_pitch * params.limit_speed_x * speed_limit_height_factor;
- update_flow_sp_sumx = true;
- }
-
- if(fabsf(manual_roll) > params.manual_threshold)
- {
- speed_body_y = manual_roll * params.limit_speed_y * speed_limit_height_factor;
- update_flow_sp_sumy = true;
- }
- }
-
- /* limit speed setpoints */
- if((speed_body_x <= params.limit_speed_x * speed_limit_height_factor) &&
- (speed_body_x >= -params.limit_speed_x * speed_limit_height_factor))
- {
- speed_sp.vx = speed_body_x;
- }
- else
- {
- if(speed_body_x > params.limit_speed_x * speed_limit_height_factor)
- speed_sp.vx = params.limit_speed_x * speed_limit_height_factor;
- if(speed_body_x < -params.limit_speed_x * speed_limit_height_factor)
- speed_sp.vx = -params.limit_speed_x * speed_limit_height_factor;
- }
-
- if((speed_body_y <= params.limit_speed_y * speed_limit_height_factor) &&
- (speed_body_y >= -params.limit_speed_y * speed_limit_height_factor))
- {
- speed_sp.vy = speed_body_y;
- }
- else
- {
- if(speed_body_y > params.limit_speed_y * speed_limit_height_factor)
- speed_sp.vy = params.limit_speed_y * speed_limit_height_factor;
- if(speed_body_y < -params.limit_speed_y * speed_limit_height_factor)
- speed_sp.vy = -params.limit_speed_y * speed_limit_height_factor;
- }
-
- /* manual yaw change */
- if(isfinite(manual_yaw) && isfinite(manual.throttle))
- {
- if(fabsf(manual_yaw) > params.manual_threshold && manual.throttle > 0.2f)
- {
- yaw_sp += manual_yaw * params.limit_yaw_step;
-
- /* modulo for rotation -pi +pi */
- if(yaw_sp < -M_PI_F)
- yaw_sp = yaw_sp + M_TWOPI_F;
- else if(yaw_sp > M_PI_F)
- yaw_sp = yaw_sp - M_TWOPI_F;
- }
- }
-
- /* forward yaw setpoint */
- speed_sp.yaw_sp = yaw_sp;
-
-
- /* manual height control
- * 0-20%: thrust linear down
- * 20%-40%: down
- * 40%-60%: stabilize altitude
- * 60-100%: up
- */
- float thrust_control = 0.0f;
-
- if (isfinite(manual.throttle))
- {
- if (start_phase)
- {
- /* control start thrust with stick input */
- if (manual.throttle < 0.4f)
- {
- /* first 40% for up to feedforward */
- thrust_control = manual.throttle / 0.4f * params.thrust_feedforward;
- }
- else
- {
- /* second 60% for up to feedforward + 10% */
- thrust_control = (manual.throttle - 0.4f) / 0.6f * 0.1f + params.thrust_feedforward;
- }
-
- /* exit start phase if setpoint is reached */
- if (height_sp < -local_pos.z && thrust_control > params.limit_thrust_lower)
- {
- start_phase = false;
- /* switch to stabilize */
- thrust_control = params.thrust_feedforward;
- }
- }
- else
- {
- if (manual.throttle < 0.2f)
- {
- /* landing initialization */
- if (!landing_initialized)
- {
- /* consider last thrust control to avoid steps */
- landing_thrust_start = speed_sp.thrust_sp;
- landing_initialized = true;
- }
-
- /* set current height as setpoint to avoid steps */
- if (-local_pos.z > params.height_min)
- height_sp = -local_pos.z;
- else
- height_sp = params.height_min;
-
- /* lower 20% stick range controls thrust down */
- thrust_control = manual.throttle / 0.2f * landing_thrust_start;
-
- /* assume ground position here */
- if (thrust_control < 0.1f)
- {
- /* reset integral if on ground */
- integrated_h_error = 0.0f;
- /* switch to start phase */
- start_phase = true;
- /* reset height setpoint */
- height_sp = params.height_min;
- }
- }
- else
- {
- /* stabilized mode */
- landing_initialized = false;
-
- /* calc new thrust with PID */
- float height_error = (local_pos.z - (-height_sp));
-
- /* update height setpoint if needed*/
- if (manual.throttle < 0.4f)
- {
- /* down */
- if (height_sp > params.height_min + params.height_rate &&
- fabsf(height_error) < params.limit_height_error)
- height_sp -= params.height_rate * dt;
- }
-
- if (manual.throttle > 0.6f)
- {
- /* up */
- if (height_sp < params.height_max &&
- fabsf(height_error) < params.limit_height_error)
- height_sp += params.height_rate * dt;
- }
-
- /* instead of speed limitation, limit height error (downwards) */
- if(height_error > params.limit_height_error)
- height_error = params.limit_height_error;
- else if(height_error < -params.limit_height_error)
- height_error = -params.limit_height_error;
-
- integrated_h_error = integrated_h_error + height_error;
- float integrated_thrust_addition = integrated_h_error * params.height_i;
-
- if(integrated_thrust_addition > params.limit_thrust_int)
- integrated_thrust_addition = params.limit_thrust_int;
- if(integrated_thrust_addition < -params.limit_thrust_int)
- integrated_thrust_addition = -params.limit_thrust_int;
-
- float height_speed = last_local_pos_z - local_pos.z;
- float thrust_diff = height_error * params.height_p - height_speed * params.height_d;
-
- thrust_control = params.thrust_feedforward + thrust_diff + integrated_thrust_addition;
-
- /* add attitude component
- * F = Fz / (cos(pitch)*cos(roll)) -> can be found in rotM
- */
-// // TODO problem with attitude
-// if (att.R_valid && att.R[2][2] > 0)
-// thrust_control = thrust_control / att.R[2][2];
-
- /* set thrust lower limit */
- if(thrust_control < params.limit_thrust_lower)
- thrust_control = params.limit_thrust_lower;
- }
- }
-
- /* set thrust upper limit */
- if(thrust_control > params.limit_thrust_upper)
- thrust_control = params.limit_thrust_upper;
- }
- /* store actual height for speed estimation */
- last_local_pos_z = local_pos.z;
-
- speed_sp.thrust_sp = thrust_control; //manual.throttle;
- speed_sp.timestamp = hrt_absolute_time();
-
- /* publish new speed setpoint */
- if(isfinite(speed_sp.vx) && isfinite(speed_sp.vy) && isfinite(speed_sp.yaw_sp) && isfinite(speed_sp.thrust_sp))
- {
-
- if(speed_setpoint_adverted)
- {
- orb_publish(ORB_ID(vehicle_bodyframe_speed_setpoint), speed_sp_pub, &speed_sp);
- }
- else
- {
- speed_sp_pub = orb_advertise(ORB_ID(vehicle_bodyframe_speed_setpoint), &speed_sp);
- speed_setpoint_adverted = true;
- }
- }
- else
- {
- warnx("NaN in flow position controller!");
- }
- }
- else
- {
- /* in manual or stabilized state just reset speed and flow sum setpoint */
- //mavlink_log_info(mavlink_fd,"[fpc] reset speed sp, flow_sp_sumx,y (%f,%f)",filtered_flow.sumx, filtered_flow.sumy);
- if(status_changed == true)
- mavlink_log_info(mavlink_fd,"[fpc] flow POSITION controller disengaged.");
-
- status_changed = false;
- speed_sp.vx = 0.0f;
- speed_sp.vy = 0.0f;
- flow_sp_sumx = filtered_flow.sumx;
- flow_sp_sumy = filtered_flow.sumy;
- if(isfinite(att.yaw))
- {
- yaw_sp = att.yaw;
- speed_sp.yaw_sp = att.yaw;
- }
- if(isfinite(manual.throttle))
- speed_sp.thrust_sp = manual.throttle;
- }
- /* measure in what intervals the controller runs */
- perf_count(mc_interval_perf);
- perf_end(mc_loop_perf);
- }
- }
-
- counter++;
- }
- else
- {
- /* sensors not ready waiting for first attitude msg */
-
- /* polling */
- struct pollfd fds[1] = {
- { .fd = vehicle_attitude_sub, .events = POLLIN },
- };
-
- /* wait for a flow msg, check for exit condition every 5 s */
- int ret = poll(fds, 1, 5000);
-
- if (ret < 0)
- {
- /* poll error, count it in perf */
- perf_count(mc_err_perf);
- }
- else if (ret == 0)
- {
- /* no return value, ignore */
- mavlink_log_info(mavlink_fd,"[fpc] no attitude received.\n");
- }
- else
- {
- if (fds[0].revents & POLLIN)
- {
- sensors_ready = true;
- mavlink_log_info(mavlink_fd,"[fpc] initialized.\n");
- }
- }
- }
- }
-
- mavlink_log_info(mavlink_fd,"[fpc] ending now...\n");
-
- thread_running = false;
-
- close(parameter_update_sub);
- close(vehicle_attitude_sub);
- close(vehicle_local_position_sub);
- close(armed_sub);
- close(control_mode_sub);
- close(manual_control_setpoint_sub);
- close(speed_sp_pub);
-
- perf_print_counter(mc_loop_perf);
- perf_free(mc_loop_perf);
-
- fflush(stdout);
- return 0;
-}
-
diff --git a/src/examples/flow_position_control/flow_position_control_params.c b/src/examples/flow_position_control/flow_position_control_params.c
deleted file mode 100644
index eb1473647..000000000
--- a/src/examples/flow_position_control/flow_position_control_params.c
+++ /dev/null
@@ -1,124 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * 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 flow_position_control_params.c
- */
-
-#include "flow_position_control_params.h"
-
-/* controller parameters */
-
-// Position control P gain
-PARAM_DEFINE_FLOAT(FPC_POS_P, 3.0f);
-// Position control D / damping gain
-PARAM_DEFINE_FLOAT(FPC_POS_D, 0.0f);
-// Altitude control P gain
-PARAM_DEFINE_FLOAT(FPC_H_P, 0.15f);
-// Altitude control I (integrator) gain
-PARAM_DEFINE_FLOAT(FPC_H_I, 0.00001f);
-// Altitude control D gain
-PARAM_DEFINE_FLOAT(FPC_H_D, 0.8f);
-// Altitude control rate limiter
-PARAM_DEFINE_FLOAT(FPC_H_RATE, 0.1f);
-// Altitude control minimum altitude
-PARAM_DEFINE_FLOAT(FPC_H_MIN, 0.5f);
-// Altitude control maximum altitude (higher than 1.5m is untested)
-PARAM_DEFINE_FLOAT(FPC_H_MAX, 1.5f);
-// Altitude control feed forward throttle - adjust to the
-// throttle position (0..1) where the copter hovers in manual flight
-PARAM_DEFINE_FLOAT(FPC_T_FFWD, 0.7f); // adjust this before flight
-PARAM_DEFINE_FLOAT(FPC_L_S_X, 1.2f);
-PARAM_DEFINE_FLOAT(FPC_L_S_Y, 1.2f);
-PARAM_DEFINE_FLOAT(FPC_L_H_ERR, 0.1f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_I, 0.05f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_U, 0.8f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_L, 0.6f);
-PARAM_DEFINE_FLOAT(FPC_L_YAW_STEP, 0.03f);
-PARAM_DEFINE_FLOAT(FPC_MAN_THR, 0.1f);
-
-
-int parameters_init(struct flow_position_control_param_handles *h)
-{
- /* PID parameters */
- h->pos_p = param_find("FPC_POS_P");
- h->pos_d = param_find("FPC_POS_D");
- h->height_p = param_find("FPC_H_P");
- h->height_i = param_find("FPC_H_I");
- h->height_d = param_find("FPC_H_D");
- h->height_rate = param_find("FPC_H_RATE");
- h->height_min = param_find("FPC_H_MIN");
- h->height_max = param_find("FPC_H_MAX");
- h->thrust_feedforward = param_find("FPC_T_FFWD");
- h->limit_speed_x = param_find("FPC_L_S_X");
- h->limit_speed_y = param_find("FPC_L_S_Y");
- h->limit_height_error = param_find("FPC_L_H_ERR");
- h->limit_thrust_int = param_find("FPC_L_TH_I");
- h->limit_thrust_upper = param_find("FPC_L_TH_U");
- h->limit_thrust_lower = param_find("FPC_L_TH_L");
- h->limit_yaw_step = param_find("FPC_L_YAW_STEP");
- h->manual_threshold = param_find("FPC_MAN_THR");
- h->rc_scale_pitch = param_find("RC_SCALE_PITCH");
- h->rc_scale_roll = param_find("RC_SCALE_ROLL");
- h->rc_scale_yaw = param_find("RC_SCALE_YAW");
-
- return OK;
-}
-
-int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p)
-{
- param_get(h->pos_p, &(p->pos_p));
- param_get(h->pos_d, &(p->pos_d));
- param_get(h->height_p, &(p->height_p));
- param_get(h->height_i, &(p->height_i));
- param_get(h->height_d, &(p->height_d));
- param_get(h->height_rate, &(p->height_rate));
- param_get(h->height_min, &(p->height_min));
- param_get(h->height_max, &(p->height_max));
- param_get(h->thrust_feedforward, &(p->thrust_feedforward));
- param_get(h->limit_speed_x, &(p->limit_speed_x));
- param_get(h->limit_speed_y, &(p->limit_speed_y));
- param_get(h->limit_height_error, &(p->limit_height_error));
- param_get(h->limit_thrust_int, &(p->limit_thrust_int));
- param_get(h->limit_thrust_upper, &(p->limit_thrust_upper));
- param_get(h->limit_thrust_lower, &(p->limit_thrust_lower));
- param_get(h->limit_yaw_step, &(p->limit_yaw_step));
- param_get(h->manual_threshold, &(p->manual_threshold));
- param_get(h->rc_scale_pitch, &(p->rc_scale_pitch));
- param_get(h->rc_scale_roll, &(p->rc_scale_roll));
- param_get(h->rc_scale_yaw, &(p->rc_scale_yaw));
-
- return OK;
-}
diff --git a/src/examples/flow_position_estimator/flow_position_estimator_main.c b/src/examples/flow_position_estimator/flow_position_estimator_main.c
index 495c415f2..c775428ef 100644
--- a/src/examples/flow_position_estimator/flow_position_estimator_main.c
+++ b/src/examples/flow_position_estimator/flow_position_estimator_main.c
@@ -65,6 +65,7 @@
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/filtered_bottom_flow.h>
#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
#include <poll.h>
#include "flow_position_estimator_params.h"
@@ -109,9 +110,9 @@ int flow_position_estimator_main(int argc, char *argv[])
thread_should_exit = false;
daemon_task = task_spawn_cmd("flow_position_estimator",
- SCHED_RR,
+ SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4096,
+ 4000,
flow_position_estimator_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_daemon_app/module.mk b/src/examples/px4_daemon_app/module.mk
index 5f8aa73d5..fc4223142 100644
--- a/src/examples/px4_daemon_app/module.mk
+++ b/src/examples/px4_daemon_app/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index 53f1b4a9a..3eaf14148 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 4096,
+ 2000,
px4_daemon_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_mavlink_debug/module.mk b/src/examples/px4_mavlink_debug/module.mk
index fefd61496..c7ef97fc4 100644
--- a/src/examples/px4_mavlink_debug/module.mk
+++ b/src/examples/px4_mavlink_debug/module.mk
@@ -37,4 +37,6 @@
MODULE_COMMAND = px4_mavlink_debug
-SRCS = px4_mavlink_debug.c \ No newline at end of file
+SRCS = px4_mavlink_debug.c
+
+MODULE_STACKSIZE = 2000
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 9584924cc..0a909d02f 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -63,11 +63,22 @@ ECL_PitchController::ECL_PitchController() :
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f)
{
+ perf_alloc(PC_COUNT, "fw att control pitch nonfinite input");
}
-float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
+ECL_PitchController::~ECL_PitchController()
{
+ perf_free(_nonfinite_input_perf);
+}
+float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
+{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(pitch_setpoint) && isfinite(roll) && isfinite(pitch) && isfinite(airspeed))) {
+ perf_count(_nonfinite_input_perf);
+ warnx("not controlling pitch");
+ return _rate_setpoint;
+ }
/* flying inverted (wings upside down) ? */
bool inverted = false;
@@ -123,6 +134,14 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
float yaw_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
+ isfinite(yaw_rate_setpoint) && isfinite(airspeed_min) &&
+ isfinite(airspeed_max) && isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
+
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
index 30a82a86a..39b9f9d03 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -51,12 +51,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_PitchController //XXX: create controller superclass
{
public:
ECL_PitchController();
+ ~ECL_PitchController();
+
float control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed);
@@ -126,6 +129,7 @@ private:
float _rate_error;
float _rate_setpoint;
float _bodyrate_setpoint;
+ perf_counter_t _nonfinite_input_perf;
};
#endif // ECL_PITCH_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 2e86c72dc..82903ef5a 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -61,10 +61,21 @@ ECL_RollController::ECL_RollController() :
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f)
{
+ perf_alloc(PC_COUNT, "fw att control roll nonfinite input");
+}
+
+ECL_RollController::~ECL_RollController()
+{
+ perf_free(_nonfinite_input_perf);
}
float ECL_RollController::control_attitude(float roll_setpoint, float roll)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll_setpoint) && isfinite(roll))) {
+ perf_count(_nonfinite_input_perf);
+ return _rate_setpoint;
+ }
/* Calculate error */
float roll_error = roll_setpoint - roll;
@@ -86,6 +97,14 @@ float ECL_RollController::control_bodyrate(float pitch,
float yaw_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(pitch) && isfinite(roll_rate) && isfinite(yaw_rate) && isfinite(yaw_rate_setpoint) &&
+ isfinite(airspeed_min) && isfinite(airspeed_max) &&
+ isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
+
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
@@ -122,8 +141,8 @@ float ECL_RollController::control_bodyrate(float pitch,
float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase if actuator is at limit
- */
+ * anti-windup: do not allow integrator to increase if actuator is at limit
+ */
if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
index 92c64b95f..0799dbe03 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -51,12 +51,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_RollController //XXX: create controller superclass
{
public:
ECL_RollController();
+ ~ECL_RollController();
+
float control_attitude(float roll_setpoint, float roll);
float control_bodyrate(float pitch,
@@ -117,6 +120,7 @@ private:
float _rate_error;
float _rate_setpoint;
float _bodyrate_setpoint;
+ perf_counter_t _nonfinite_input_perf;
};
#endif // ECL_ROLL_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
index 255776765..e53ffc644 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -60,12 +60,25 @@ ECL_YawController::ECL_YawController() :
_bodyrate_setpoint(0.0f),
_coordinated_min_speed(1.0f)
{
+ perf_alloc(PC_COUNT, "fw att control yaw nonfinite input");
+}
+
+ECL_YawController::~ECL_YawController()
+{
+ perf_free(_nonfinite_input_perf);
}
float ECL_YawController::control_attitude(float roll, float pitch,
float speed_body_u, float speed_body_v, float speed_body_w,
float roll_rate_setpoint, float pitch_rate_setpoint)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(speed_body_u) && isfinite(speed_body_v) &&
+ isfinite(speed_body_w) && isfinite(roll_rate_setpoint) &&
+ isfinite(pitch_rate_setpoint))) {
+ perf_count(_nonfinite_input_perf);
+ return _rate_setpoint;
+ }
// static int counter = 0;
/* Calculate desired yaw rate from coordinated turn constraint / (no side forces) */
_rate_setpoint = 0.0f;
@@ -103,6 +116,13 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
float pitch_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
+ isfinite(pitch_rate_setpoint) && isfinite(airspeed_min) &&
+ isfinite(airspeed_max) && isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
index 03f3202d0..a360c14b8 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -50,12 +50,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_YawController //XXX: create controller superclass
{
public:
ECL_YawController();
+ ~ECL_YawController();
+
float control_attitude(float roll, float pitch,
float speed_body_u, float speed_body_v, float speed_body_w,
float roll_rate_setpoint, float pitch_rate_setpoint);
@@ -118,6 +121,7 @@ private:
float _rate_setpoint;
float _bodyrate_setpoint;
float _coordinated_min_speed;
+ perf_counter_t _nonfinite_input_perf;
};
diff --git a/src/lib/version/version.h b/src/lib/version/version.h
index af733aaf0..d8ccb6774 100644
--- a/src/lib/version/version.h
+++ b/src/lib/version/version.h
@@ -59,4 +59,8 @@
#define HW_ARCH "PX4FMU_V2"
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+#define HW_ARCH "AEROCORE"
+#endif
+
#endif /* VERSION_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 ec679f1ae..807f53020 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012-2014 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
@@ -34,9 +32,12 @@
****************************************************************************/
/*
- * @file attitude_estimator_ekf_main.c
+ * @file attitude_estimator_ekf_main.cpp
*
* Extended Kalman Filter for Attitude Estimation.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
@@ -111,7 +112,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_create().
+ * to task_spawn_cmd().
*/
int attitude_estimator_ekf_main(int argc, char *argv[])
{
@@ -265,7 +266,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
- int printcounter = 0;
thread_running = true;
@@ -273,9 +273,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
// struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
// orb_advert_t pub_dbg = -1;
- float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
- // XXX write this out to perf regs
-
/* keep track of sensor updates */
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
@@ -286,11 +283,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* initialize parameter handles */
parameters_init(&ekf_param_handles);
- uint64_t start_time = hrt_absolute_time();
bool initialized = false;
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
- unsigned offset_count = 0;
/* rotation matrix for magnetic declination */
math::Matrix<3, 3> R_decl;
@@ -381,7 +376,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* Fill in gyro measurements */
if (sensor_last_timestamp[0] != raw.timestamp) {
update_vect[0] = 1;
- sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
+ // sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -392,7 +387,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update accelerometer measurements */
if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
update_vect[1] = 1;
- sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
+ // sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
@@ -444,7 +439,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update magnetometer measurements */
if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
update_vect[2] = 1;
- sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
+ // sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
@@ -497,8 +492,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- uint64_t timing_start = hrt_absolute_time();
-
attitudeKalmanfilter(update_vect, dt, z_k, x_aposteriori_k, P_aposteriori_k, ekf_params.q, ekf_params.r,
euler, Rot_matrix, x_aposteriori, P_aposteriori);
diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk
index d98647f99..99d0c5bf2 100644
--- a/src/modules/attitude_estimator_ekf/module.mk
+++ b/src/modules/attitude_estimator_ekf/module.mk
@@ -50,3 +50,5 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/rtGetNaN.c \
codegen/norm.c \
codegen/cross.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index 3653defa6..e55b01160 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Hyon Lim <limhyon@gmail.com>
- * Anton Babushkin <anton.babushkin@me.com>
+ * 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
@@ -36,6 +34,9 @@
/*
* @file attitude_estimator_so3_main.cpp
*
+ * @author Hyon Lim <limhyon@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* Implementation of nonlinear complementary filters on the SO(3).
* This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
* Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
@@ -131,7 +132,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_create().
+ * to task_spawn_cmd().
*/
int attitude_estimator_so3_main(int argc, char *argv[])
{
diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk
index e29bb16a6..f52715abb 100644
--- a/src/modules/attitude_estimator_so3/module.mk
+++ b/src/modules/attitude_estimator_so3/module.mk
@@ -6,3 +6,5 @@ MODULE_COMMAND = attitude_estimator_so3
SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 1cbdf9bf8..7180048ff 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -194,13 +194,13 @@ int do_accel_calibration(int mavlink_fd)
int32_t board_rotation_int;
param_get(board_rotation_h, &(board_rotation_int));
enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
- math::Matrix<3,3> board_rotation;
+ math::Matrix<3, 3> board_rotation;
get_rot_matrix(board_rotation_id, &board_rotation);
- math::Matrix<3,3> board_rotation_t = board_rotation.transposed();
+ math::Matrix<3, 3> board_rotation_t = board_rotation.transposed();
math::Vector<3> accel_offs_vec(&accel_offs[0]);
- math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec;
- math::Matrix<3,3> accel_T_mat(&accel_T[0][0]);
- math::Matrix<3,3> accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+ math::Vector<3> accel_offs_rotated = board_rotation_t *accel_offs_vec;
+ math::Matrix<3, 3> accel_T_mat(&accel_T[0][0]);
+ math::Matrix<3, 3> accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation;
accel_scale.x_offset = accel_offs_rotated(0);
accel_scale.x_scale = accel_T_rotated(0, 0);
@@ -277,11 +277,13 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
}
- if (old_done_count != done_count)
+ if (old_done_count != done_count) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
+ }
- if (done)
+ if (done) {
break;
+ }
mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
(!data_collected[0]) ? "x+ " : "",
@@ -380,11 +382,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
- if (d > still_thr2 * 8.0f)
+ if (d > still_thr2 * 8.0f) {
d = still_thr2 * 8.0f;
+ }
- if (d > accel_disp[i])
+ if (d > accel_disp[i]) {
accel_disp[i] = d;
+ }
}
/* still detector with hysteresis */
@@ -432,33 +436,39 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 0; // [ g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 0; // [ g, 0, 0 ]
+ }
if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 1; // [ -g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 1; // [ -g, 0, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 2; // [ 0, g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 2; // [ 0, g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 3; // [ 0, -g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 3; // [ 0, -g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
- return 4; // [ 0, 0, g ]
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr) {
+ return 4; // [ 0, 0, g ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
- return 5; // [ 0, 0, -g ]
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr) {
+ return 5; // [ 0, 0, -g ]
+ }
mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
@@ -485,8 +495,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
struct sensor_combined_s sensor;
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- for (int i = 0; i < 3; i++)
+ for (int i = 0; i < 3; i++) {
accel_sum[i] += sensor.accelerometer_m_s2[i];
+ }
count++;
@@ -495,8 +506,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
continue;
}
- if (errcount > samples_num / 10)
+ if (errcount > samples_num / 10) {
return ERROR;
+ }
}
for (int i = 0; i < 3; i++) {
@@ -512,8 +524,9 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0f)
- return ERROR; // Singular matrix
+ if (det == 0.0f) {
+ return ERROR; // Singular matrix
+ }
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
@@ -549,8 +562,9 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* calculate inverse matrix for A */
float mat_A_inv[3][3];
- if (mat_invert3(mat_A, mat_A_inv) != OK)
+ if (mat_invert3(mat_A, mat_A_inv) != OK) {
return ERROR;
+ }
/* copy results to accel_T */
for (int i = 0; i < 3; i++) {
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index c8c7a42e7..5d21d89d0 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -82,12 +82,15 @@ int do_airspeed_calibration(int mavlink_fd)
bool paramreset_successful = false;
int fd = open(AIRSPEED_DEVICE_PATH, 0);
+
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+
} else {
mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
+
close(fd);
}
@@ -112,8 +115,9 @@ int do_airspeed_calibration(int mavlink_fd)
diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 4f64b5c99..77d810a81 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -221,7 +221,7 @@ void print_status();
transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy);
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy);
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
@@ -233,8 +233,9 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
int commander_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
usage("missing command");
+ }
if (!strcmp(argv[1], "start")) {
@@ -248,7 +249,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 3000,
+ 2950,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -261,8 +262,9 @@ int commander_main(int argc, char *argv[])
if (!strcmp(argv[1], "stop")) {
- if (!thread_running)
+ if (!thread_running) {
errx(0, "commander already stopped");
+ }
thread_should_exit = true;
@@ -304,8 +306,9 @@ int commander_main(int argc, char *argv[])
void usage(const char *reason)
{
- if (reason)
+ if (reason) {
fprintf(stderr, "%s\n", reason);
+ }
fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
exit(1);
@@ -364,20 +367,22 @@ void print_status()
static orb_advert_t status_pub;
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy)
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy)
{
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
- // output appropriate error messages if the state cannot transition.
- arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
- if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
- mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
- } else if (arming_res == TRANSITION_DENIED) {
- tune_negative(true);
- }
-
- return arming_res;
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
+ // output appropriate error messages if the state cannot transition.
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
+
+ if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
+ mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
+
+ } else if (arming_res == TRANSITION_DENIED) {
+ tune_negative(true);
+ }
+
+ return arming_res;
}
bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
@@ -414,43 +419,61 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* set main state */
transition_result_t main_res = TRANSITION_DENIED;
- if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
- /* use autopilot-specific mode */
- if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (hil_ret == OK) {
+ ret = true;
+ }
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
- /* SEATBELT */
- main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ // Transition the arming state
+ arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ if (arming_res == TRANSITION_CHANGED) {
+ ret = true;
+ }
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
main_res = main_state_transition(status, MAIN_STATE_AUTO);
}
- } else {
- /* use base mode */
- if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
- /* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
+ /* ALTCTL */
+ main_res = main_state_transition(status, MAIN_STATE_ALTCTL);
- } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
- if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
+ /* ACRO */
+ main_res = main_state_transition(status, MAIN_STATE_ACRO);
+ }
- } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
- /* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ } else {
+ /* use base mode */
+ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
+ /* AUTO */
+ main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
+ if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+
+ } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
+ /* MANUAL */
+ main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
}
}
}
+ if (main_res == TRANSITION_CHANGED) {
+ ret = true;
+ }
if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
@@ -463,24 +486,28 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
- // We use an float epsilon delta to test float equality.
- if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
+ // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
+ // We use an float epsilon delta to test float equality.
+ if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
- } else {
- // Flick to inair restore first if this comes from an onboard system
- if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
- status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
- }
- transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
- if (arming_res == TRANSITION_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- } else {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- }
- }
+ } else {
+
+ // Flick to inair restore first if this comes from an onboard system
+ if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
+ status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
+ }
+
+ transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
+
+ if (arming_res == TRANSITION_DENIED) {
+ mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ }
+ }
}
break;
@@ -504,7 +531,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
break;
- /* Flight termination */
+ /* Flight termination */
case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
//XXX: to enable the parachute, a param needs to be set
@@ -523,6 +550,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
case VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
+
if (use_current) {
/* use current position */
if (status->condition_global_position_valid) {
@@ -566,6 +594,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
break;
+
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
@@ -579,6 +608,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
+
if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, result);
@@ -612,9 +642,10 @@ int commander_thread_main(int argc, char *argv[])
char *main_states_str[MAIN_STATE_MAX];
main_states_str[0] = "MANUAL";
- main_states_str[1] = "SEATBELT";
- main_states_str[2] = "EASY";
+ main_states_str[1] = "ALTCTL";
+ main_states_str[2] = "POSCTL";
main_states_str[3] = "AUTO";
+ main_states_str[4] = "ACRO";
char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[0] = "INIT";
@@ -705,7 +736,7 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2900);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
@@ -860,6 +891,7 @@ int commander_thread_main(int argc, char *argv[])
/* re-check RC calibration */
rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
}
+
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
param_get(_param_enable_parachute, &parachute_enabled);
@@ -900,6 +932,7 @@ int commander_thread_main(int argc, char *argv[])
/* disarm if safety is now on and still armed */
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+
if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) {
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch");
}
@@ -925,9 +958,11 @@ int commander_thread_main(int argc, char *argv[])
/* update condition_global_position_valid */
/* hysteresis for EPH/EPV */
bool eph_epv_good;
+
if (status.condition_global_position_valid) {
if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) {
eph_epv_good = false;
+
} else {
eph_epv_good = true;
}
@@ -935,17 +970,19 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) {
eph_epv_good = true;
+
} else {
eph_epv_good = false;
}
}
+
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed);
/* check if GPS fix is ok */
/* update home position */
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
home.lat = global_position.lat;
home.lon = global_position.lon;
@@ -972,7 +1009,26 @@ int commander_thread_main(int argc, char *argv[])
}
/* update condition_local_position_valid and condition_local_altitude_valid */
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && eph_epv_good, &(status.condition_local_position_valid), &status_changed);
+ /* hysteresis for EPH */
+ bool local_eph_good;
+
+ if (status.condition_global_position_valid) {
+ if (local_position.eph > eph_epv_threshold * 2.0f) {
+ local_eph_good = false;
+
+ } else {
+ local_eph_good = true;
+ }
+
+ } else {
+ if (local_position.eph < eph_epv_threshold) {
+ local_eph_good = true;
+
+ } else {
+ local_eph_good = false;
+ }
+ }
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
if (status.condition_local_altitude_valid) {
@@ -1050,8 +1106,9 @@ int commander_thread_main(int argc, char *argv[])
/* compute system load */
uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
- if (last_idle_time > 0)
- status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ if (last_idle_time > 0) {
+ status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ }
last_idle_time = system_load.tasks[0].total_runtime;
@@ -1127,22 +1184,22 @@ int commander_thread_main(int argc, char *argv[])
status.rc_signal_lost = false;
- transition_result_t res; // store all transitions results here
+ transition_result_t arming_res; // store all transitions results here
/* arm/disarm by RC */
- res = TRANSITION_NOT_CHANGED;
+ arming_res = TRANSITION_NOT_CHANGED;
- /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm
+ /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSIST mode and landed) -> disarm
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
- sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ (status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
+ sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- res = arming_state_transition(&status, &safety, new_arming_state, &armed);
+ arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed);
stick_off_counter = 0;
} else {
@@ -1155,16 +1212,16 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position and we're in MANUAL mode -> arm */
if (status.arming_state == ARMING_STATE_STANDBY &&
- sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ sp_man.r > STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
+ print_reject_arm("#audio: NOT ARMING: Press safety switch first.");
} else if (status.main_state != MAIN_STATE_MANUAL) {
- print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+ print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
} else {
- res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
}
stick_on_counter = 0;
@@ -1177,7 +1234,7 @@ int commander_thread_main(int argc, char *argv[])
stick_on_counter = 0;
}
- if (res == TRANSITION_CHANGED) {
+ if (arming_res == TRANSITION_CHANGED) {
if (status.arming_state == ARMING_STATE_ARMED) {
mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
@@ -1185,24 +1242,24 @@ int commander_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
}
- } else if (res == TRANSITION_DENIED) {
+ } else if (arming_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied");
}
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* recover from failsafe */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
/* evaluate the main state machine according to mode switches */
- res = set_main_state_rc(&status, &sp_man);
+ transition_result_t main_res = set_main_state_rc(&status, &sp_man);
/* play tune on mode change only if armed, blink LED always */
- if (res == TRANSITION_CHANGED) {
+ if (main_res == TRANSITION_CHANGED) {
tune_positive(armed.armed);
- } else if (res == TRANSITION_DENIED) {
+ } else if (main_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: main state transition denied");
}
@@ -1215,7 +1272,8 @@ int commander_thread_main(int argc, char *argv[])
} else {
- /* MISSION switch */
+
+ /* LOITER switch */
if (sp_man.loiter_switch == SWITCH_POS_ON) {
/* stick is in LOITER position */
status.set_nav_state = NAVIGATION_STATE_LOITER;
@@ -1225,7 +1283,7 @@ int commander_thread_main(int argc, char *argv[])
status.set_nav_state = NAVIGATION_STATE_MISSION;
} else if ((sp_man.return_switch == SWITCH_POS_OFF || sp_man.return_switch == SWITCH_POS_MIDDLE) &&
- pos_sp_triplet.nav_state == NAV_STATE_RTL) {
+ pos_sp_triplet.nav_state == NAV_STATE_RTL) {
/* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
status.set_nav_state = NAVIGATION_STATE_MISSION;
}
@@ -1241,27 +1299,20 @@ int commander_thread_main(int argc, char *argv[])
if (armed.armed) {
if (status.main_state == MAIN_STATE_AUTO) {
/* check if AUTO mode still allowed */
- transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO);
+ transition_result_t auto_res = main_state_transition(&status, MAIN_STATE_AUTO);
- if (res == TRANSITION_NOT_CHANGED) {
+ if (auto_res == TRANSITION_NOT_CHANGED) {
last_auto_state_valid = hrt_absolute_time();
}
/* still invalid state after the timeout interval, execute failsafe */
- if ((hrt_elapsed_time(&last_auto_state_valid) > FAILSAFE_DEFAULT_TIMEOUT) && (res == TRANSITION_DENIED)) {
+ if ((hrt_elapsed_time(&last_auto_state_valid) > FAILSAFE_DEFAULT_TIMEOUT) && (auto_res == TRANSITION_DENIED)) {
/* AUTO mode denied, don't try RTL, switch to failsafe state LAND */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ auto_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_DENIED) {
+ if (auto_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
-
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: TERMINATION");
- }
-
- } else if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: LANDING");
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
} else {
status.set_nav_state = NAVIGATION_STATE_MISSION;
@@ -1269,47 +1320,37 @@ int commander_thread_main(int argc, char *argv[])
} else {
/* failsafe for manual modes */
- transition_result_t res = TRANSITION_DENIED;
+ transition_result_t manual_res = TRANSITION_DENIED;
if (!status.condition_landed) {
/* vehicle is not landed, try to perform RTL */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
-
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: RETURN TO LAND");
- }
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
}
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* RTL not allowed (no global position estimate) or not wanted, try LAND */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: LANDING");
- }
-
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
- } else if (res == TRANSITION_CHANGED) {
- mavlink_log_critical(mavlink_fd, "#a FAILSAFE: TERMINATION");
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
} else {
status.set_nav_state = NAVIGATION_STATE_RTL;
- }
+ }
}
} else {
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* reset failsafe when disarmed */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
}
}
// TODO remove this hack
- /* flight termination in manual mode if assisted switch is on easy position */
- if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch == SWITCH_POS_ON) {
+ /* flight termination in manual mode if assist switch is on POSCTL position */
+ if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctl_switch == SWITCH_POS_ON) {
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
tune_positive(armed.armed);
}
@@ -1323,8 +1364,9 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub))
+ if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub)) {
status_changed = true;
+ }
}
/* check which state machines for changes, clear "changed" flag */
@@ -1341,7 +1383,7 @@ int commander_thread_main(int argc, char *argv[])
/* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
// TODO remove code duplication
home.lat = global_position.lat;
@@ -1353,7 +1395,7 @@ int commander_thread_main(int argc, char *argv[])
home.z = local_position.z;
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "#audio: home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
/* announce new home position */
if (home_pub > 0) {
@@ -1367,6 +1409,7 @@ int commander_thread_main(int argc, char *argv[])
status.condition_home_position_valid = true;
}
}
+
was_armed = armed.armed;
if (main_state_changed) {
@@ -1530,21 +1573,24 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
} else if (actuator_armed->ready_to_arm) {
/* ready to arm, blink at 1Hz */
- if (leds_counter % 20 == 0)
+ if (leds_counter % 20 == 0) {
led_toggle(LED_BLUE);
+ }
} else {
/* not ready to arm, blink at 10Hz */
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_BLUE);
+ }
}
#endif
/* give system warnings on error LED, XXX maybe add memory usage warning too */
if (status->load > 0.95f) {
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_AMBER);
+ }
} else {
led_off(LED_AMBER);
@@ -1565,30 +1611,35 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_OFF: // MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (sp_man->acro_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_ACRO);
+
+ } else {
+ res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
// TRANSITION_DENIED is not possible here
break;
- case SWITCH_POS_MIDDLE: // ASSISTED
- if (sp_man->assisted_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_EASY);
+ case SWITCH_POS_MIDDLE: // ASSIST
+ if (sp_man->posctl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_POSCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT
- print_reject_mode(status, "EASY");
+ // else fallback to ALTCTL
+ print_reject_mode(status, "POSCTL");
}
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
- if (sp_man->assisted_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "SEATBELT");
+ if (sp_man->posctl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status, "ALTCTL");
}
// else fallback to MANUAL
@@ -1603,9 +1654,9 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT (EASY likely will not work too)
+ // else fallback to ALTCTL (POSCTL likely will not work too)
print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
@@ -1651,7 +1702,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ALTCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1662,7 +1713,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1675,6 +1726,18 @@ set_control_mode()
case MAIN_STATE_AUTO:
navigator_enabled = true;
+ break;
+
+ case MAIN_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
default:
break;
@@ -1758,7 +1821,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
- tune_positive(true);
+ tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
@@ -1772,7 +1835,8 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command);
+ /* this needs additional hints to the user - so let other messages pass and be spoken */
+ mavlink_log_critical(mavlink_fd, "command temporarily rejected: %u", cmd.command);
tune_negative(true);
break;
@@ -1808,8 +1872,9 @@ void *commander_low_prio_loop(void *arg)
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
/* timed out - periodic check for thread_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1824,8 +1889,9 @@ void *commander_low_prio_loop(void *arg)
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
- cmd.command == VEHICLE_CMD_DO_SET_SERVO)
+ cmd.command == VEHICLE_CMD_DO_SET_SERVO) {
continue;
+ }
/* only handle low-priority commands here */
switch (cmd.command) {
@@ -1903,6 +1969,7 @@ void *commander_low_prio_loop(void *arg)
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
@@ -1917,10 +1984,12 @@ void *commander_low_prio_loop(void *arg)
}
- if (calib_ret == OK)
+ if (calib_ret == OK) {
tune_positive(true);
- else
+
+ } else {
tune_negative(true);
+ }
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
@@ -1940,11 +2009,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters load ERROR");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1960,11 +2031,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters save error");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1974,8 +2047,8 @@ void *commander_low_prio_loop(void *arg)
}
case VEHICLE_CMD_START_RX_PAIR:
- /* handled in the IO driver */
- break;
+ /* handled in the IO driver */
+ break;
default:
/* don't answer on unsupported commands, it will be done in main loop */
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 0fd3c9e9e..940a04aa1 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -113,17 +113,22 @@ void buzzer_deinit()
close(buzzer);
}
-void set_tune(int tune) {
+void set_tune(int tune)
+{
unsigned int new_tune_duration = tune_durations[tune];
+
/* don't interrupt currently playing non-repeating tune by repeating */
if (tune_end == 0 || new_tune_duration != 0 || hrt_absolute_time() > tune_end) {
/* allow interrupting current non-repeating tune by the same tune */
if (tune != tune_current || new_tune_duration != 0) {
ioctl(buzzer, TONE_SET_ALARM, tune);
}
+
tune_current = tune;
+
if (new_tune_duration != 0) {
tune_end = hrt_absolute_time() + new_tune_duration;
+
} else {
tune_end = 0;
}
@@ -138,6 +143,7 @@ void tune_positive(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_GREEN);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_POSITIVE_TUNE);
}
@@ -151,6 +157,7 @@ void tune_neutral(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_WHITE);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEUTRAL_TUNE);
}
@@ -164,6 +171,7 @@ void tune_negative(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_RED);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEGATIVE_TUNE);
}
@@ -198,7 +206,7 @@ int led_init()
return ERROR;
}
- /* the blue LED is only available on FMUv1 but not FMUv2 */
+ /* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
(void)ioctl(leds, LED_ON, LED_BLUE);
/* we consider the amber led mandatory */
@@ -244,22 +252,25 @@ int led_off(int led)
void rgbled_set_color(rgbled_color_t color)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+ }
}
void rgbled_set_mode(rgbled_mode_t mode)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+ }
}
void rgbled_set_pattern(rgbled_pattern_t *pattern)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+ }
}
float battery_remaining_estimate_voltage(float voltage, float discharged)
@@ -299,6 +310,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged)
if (bat_capacity > 0.0f) {
/* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
+
} else {
/* else use voltage */
ret = remaining_voltage;
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 8a946543d..ee0d08391 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -317,34 +317,34 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to SEATBELT.
+ // MANUAL to ALTCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_SEATBELT;
- ut_assert("tranisition: manual to seatbelt",
+ new_main_state = MAIN_STATE_ALTCTL;
+ ut_assert("tranisition: manual to altctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
+ ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state);
- // MANUAL to SEATBELT, invalid local altitude.
+ // MANUAL to ALTCTRL, invalid local altitude.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = false;
- new_main_state = MAIN_STATE_SEATBELT;
+ new_main_state = MAIN_STATE_ALTCTL;
ut_assert("no transition: invalid local altitude",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to EASY.
+ // MANUAL to POSCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_EASY;
- ut_assert("transition: manual to easy",
+ new_main_state = MAIN_STATE_POSCTL;
+ ut_assert("transition: manual to posctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
+ ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state);
- // MANUAL to EASY, invalid local position.
+ // MANUAL to POSCTRL, invalid local position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = false;
- new_main_state = MAIN_STATE_EASY;
+ new_main_state = MAIN_STATE_POSCTL;
ut_assert("no transition: invalid position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 30cd0d48d..cbc2844c1 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -110,8 +110,9 @@ int do_gyro_calibration(int mavlink_fd)
gyro_scale.z_offset += gyro_report.z;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else {
poll_errcount++;
@@ -163,8 +164,9 @@ int do_gyro_calibration(int mavlink_fd)
/* apply new offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale)) {
warn("WARNING: failed to apply new offsets for gyro");
+ }
close(fd);
@@ -178,9 +180,9 @@ int do_gyro_calibration(int mavlink_fd)
float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+ if (mag_last > M_PI_F) { mag_last -= 2 * M_PI_F; }
- if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
+ if (mag_last < -M_PI_F) { mag_last += 2 * M_PI_F; }
uint64_t last_time = hrt_absolute_time();
@@ -220,15 +222,15 @@ int do_gyro_calibration(int mavlink_fd)
//float mag = -atan2f(magNav(1),magNav(0));
float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2 * M_PI_F;
+ if (mag > M_PI_F) { mag -= 2 * M_PI_F; }
- if (mag < -M_PI_F) mag += 2 * M_PI_F;
+ if (mag < -M_PI_F) { mag += 2 * M_PI_F; }
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2 * M_PI_F;
+ if (diff > M_PI_F) { diff -= 2 * M_PI_F; }
- if (diff < -M_PI_F) diff += 2 * M_PI_F;
+ if (diff < -M_PI_F) { diff += 2 * M_PI_F; }
baseline_integral += diff;
mag_last = mag;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 4ebf266f4..0ead22f77 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_interval = 45 * 1000 * 1000;
/* maximum 500 values */
- const unsigned int calibration_maxcount = 500;
+ const unsigned int calibration_maxcount = 240;
unsigned int calibration_counter;
struct mag_scale mscale_null = {
@@ -121,9 +121,24 @@ int do_mag_calibration(int mavlink_fd)
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+
+ /* clean up */
+ if (x != NULL) {
+ free(x);
+ }
+
+ if (y != NULL) {
+ free(y);
+ }
+
+ if (z != NULL) {
+ free(z);
+ }
+
res = ERROR;
return res;
}
+
} else {
/* exit */
return ERROR;
@@ -163,8 +178,9 @@ int do_mag_calibration(int mavlink_fd)
calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
+ if (calibration_counter % (calibration_maxcount / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ }
} else {
poll_errcount++;
@@ -198,14 +214,17 @@ int do_mag_calibration(int mavlink_fd)
}
}
- if (x != NULL)
+ if (x != NULL) {
free(x);
+ }
- if (y != NULL)
+ if (y != NULL) {
free(y);
+ }
- if (z != NULL)
+ if (z != NULL) {
free(z);
+ }
if (res == OK) {
/* apply calibration and set parameters */
@@ -234,23 +253,29 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
/* set parameters */
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
res = ERROR;
+ }
if (res != OK) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 554dfcb08..27ca5c182 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,3 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index 2144d3460..e0f8dc95d 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -12,9 +12,10 @@
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
- PX4_CUSTOM_MAIN_MODE_SEATBELT,
- PX4_CUSTOM_MAIN_MODE_EASY,
+ PX4_CUSTOM_MAIN_MODE_ALTCTL,
+ PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_ACRO,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 41f3ca0aa..0776894fb 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -69,11 +69,11 @@ int do_trim_calibration(int mavlink_fd)
orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
/* set parameters */
- float p = sp.roll;
+ float p = sp.y;
param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
+ p = sp.x;
param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
+ p = sp.r;
param_set(param_find("TRIM_YAW"), &p);
/* store to permanent storage */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 8dc616730..6f0e9794a 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -75,38 +75,38 @@ static bool failsafe_state_changed = true;
// though the transition is marked as true additional checks must be made. See arming_state_transition
// code for those checks.
static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
- // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
- { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
- { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
- { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
- { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
- { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
- { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
- { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
};
// You can index into the array with an arming_state_t in order to get it's textual representation
-static const char* state_names[ARMING_STATE_MAX] = {
- "ARMING_STATE_INIT",
- "ARMING_STATE_STANDBY",
- "ARMING_STATE_ARMED",
- "ARMING_STATE_ARMED_ERROR",
- "ARMING_STATE_STANDBY_ERROR",
- "ARMING_STATE_REBOOT",
- "ARMING_STATE_IN_AIR_RESTORE",
+static const char *state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
};
transition_result_t
arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
- const struct safety_s *safety, /// current safety settings
- arming_state_t new_arming_state, /// arming state requested
- struct actuator_armed_s *armed, /// current armed status
- const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
- // Double check that our static arrays are still valid
- ASSERT(ARMING_STATE_INIT == 0);
- ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
-
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
+
/*
* Perform an atomic state update
*/
@@ -117,63 +117,70 @@ arming_state_transition(struct vehicle_status_s *status, /// current
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == status->arming_state) {
ret = TRANSITION_NOT_CHANGED;
+
} else {
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
+
} else {
armed->lockdown = false;
}
-
- // Check that we have a valid state transition
- bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
- if (valid_transition) {
- // We have a good transition. Now perform any secondary validation.
- if (new_arming_state == ARMING_STATE_ARMED) {
- // Fail transition if we need safety switch press
- // Allow if coming from in air restore
- // Allow if HIL_STATE_ON
- if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first.");
- }
- valid_transition = false;
- }
- } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
- new_arming_state = ARMING_STATE_STANDBY_ERROR;
- }
- }
-
- // HIL can always go to standby
- if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
- valid_transition = true;
- }
-
- /* Sensors need to be initialized for STANDBY state */
- if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
- valid_transition = false;
- }
-
- // Finish up the state transition
- if (valid_transition) {
- armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
- armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
- ret = TRANSITION_CHANGED;
- status->arming_state = new_arming_state;
- arming_state_changed = true;
- }
- }
-
+
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
+
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ // Fail transition if we need safety switch press
+ // Allow if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch first.");
+ }
+
+ valid_transition = false;
+ }
+
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
+ }
+ }
+
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
+
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
+ }
+
+ // Finish up the state transition
+ if (valid_transition) {
+ armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
+ armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
+ ret = TRANSITION_CHANGED;
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
/* end of atomic state update */
irqrestore(flags);
- if (ret == TRANSITION_DENIED) {
- static const char* errMsg = "Invalid arming transition from %s to %s";
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
- warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "Invalid arming transition from %s to %s";
+
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
+
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
@@ -215,7 +222,11 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_ALTCTL:
/* need at minimum altitude estimate */
if (!status->is_rotary_wing ||
@@ -226,7 +237,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
@@ -301,7 +312,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
case HIL_STATE_OFF:
/* we're in HIL and unexpected things can happen if we disable HIL now */
- mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
+ mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
valid_transition = false;
break;
@@ -320,6 +331,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
/* list directory */
DIR *d;
d = opendir("/dev");
+
if (d) {
struct dirent *direntry;
@@ -331,26 +343,32 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
if (!strncmp("tty", direntry->d_name, 3)) {
continue;
}
+
/* skip mtd devices */
if (!strncmp("mtd", direntry->d_name, 3)) {
continue;
}
+
/* skip ram devices */
if (!strncmp("ram", direntry->d_name, 3)) {
continue;
}
+
/* skip MMC devices */
if (!strncmp("mmc", direntry->d_name, 3)) {
continue;
}
+
/* skip mavlink */
if (!strcmp("mavlink", direntry->d_name)) {
continue;
}
+
/* skip console */
if (!strcmp("console", direntry->d_name)) {
continue;
}
+
/* skip null */
if (!strcmp("null", direntry->d_name)) {
continue;
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 7505ba358..1a65313e8 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Jean Cyr
- * Lorenz Meier
- * Julian Oes
- * Thomas Gubler
+ * Copyright (c) 2013, 2014 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
@@ -37,6 +33,11 @@
/**
* @file dataman.c
* DATAMANAGER driver.
+ *
+ * @author Jean Cyr
+ * @author Lorenz Meier
+ * @author Julian Oes
+ * @author Thomas Gubler
*/
#include <nuttx/config.h>
@@ -62,7 +63,7 @@ __EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t
__EXPORT int dm_clear(dm_item_t item);
__EXPORT int dm_restart(dm_reset_reason restart_type);
-/* Types of function calls supported by the worker task */
+/** Types of function calls supported by the worker task */
typedef enum {
dm_write_func = 0,
dm_read_func,
@@ -71,11 +72,12 @@ typedef enum {
dm_number_of_funcs
} dm_function_t;
-/* Work task work item */
+/** Work task work item */
typedef struct {
sq_entry_t link; /**< list linkage */
sem_t wait_sem;
- dm_function_t func;
+ unsigned char first;
+ unsigned char func;
ssize_t result;
union {
struct {
@@ -100,6 +102,8 @@ typedef struct {
};
} work_q_item_t;
+const size_t k_work_item_allocation_chunk_size = 8;
+
/* Usage statistics */
static unsigned g_func_counts[dm_number_of_funcs];
@@ -177,9 +181,23 @@ create_work_item(void)
unlock_queue(&g_free_q);
- /* If we there weren't any free items then obtain memory for a new one */
- if (item == NULL)
- item = (work_q_item_t *)malloc(sizeof(work_q_item_t));
+ /* If we there weren't any free items then obtain memory for a new ones */
+ if (item == NULL) {
+ item = (work_q_item_t *)malloc(k_work_item_allocation_chunk_size * sizeof(work_q_item_t));
+ if (item) {
+ item->first = 1;
+ lock_queue(&g_free_q);
+ for (int i = 1; i < k_work_item_allocation_chunk_size; i++) {
+ (item + i)->first = 0;
+ sq_addfirst(&(item + i)->link, &(g_free_q.q));
+ }
+ /* Update the queue size and potentially the maximum queue size */
+ g_free_q.size += k_work_item_allocation_chunk_size - 1;
+ if (g_free_q.size > g_free_q.max_size)
+ g_free_q.max_size = g_free_q.size;
+ unlock_queue(&g_free_q);
+ }
+ }
/* If we got one then lock the item*/
if (item)
@@ -411,7 +429,7 @@ _clear(dm_item_t item)
return result;
}
-/* Tell the data manager about the type of the last reset */
+/** Tell the data manager about the type of the last reset */
static int
_restart(dm_reset_reason reason)
{
@@ -480,7 +498,7 @@ _restart(dm_reset_reason reason)
return result;
}
-/* write to the data manager file */
+/** Write to the data manager file */
__EXPORT ssize_t
dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
{
@@ -505,7 +523,7 @@ dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const
return (ssize_t)enqueue_work_item_and_wait_for_result(work);
}
-/* Retrieve from the data manager file */
+/** Retrieve from the data manager file */
__EXPORT ssize_t
dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
{
@@ -717,8 +735,8 @@ task_main(int argc, char *argv[])
for (;;) {
if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
break;
-
- free(work);
+ if (work->first)
+ free(work);
}
destroy_q(&g_work_q);
@@ -736,7 +754,7 @@ start(void)
sem_init(&g_init_sema, 1, 0);
/* start the worker thread */
- if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) {
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2000, task_main, NULL)) <= 0) {
warn("task start failed");
return -1;
}
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index 4382baeb5..1dfb26f73 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 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
@@ -46,7 +46,7 @@
extern "C" {
#endif
- /* Types of items that the data manager can store */
+ /** Types of items that the data manager can store */
typedef enum {
DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */
DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */
@@ -56,7 +56,7 @@ extern "C" {
DM_KEY_NUM_KEYS /* Total number of item types defined */
} dm_item_t;
- /* The maximum number of instances for each item type */
+ /** The maximum number of instances for each item type */
enum {
DM_KEY_SAFE_POINTS_MAX = 8,
DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
@@ -65,24 +65,24 @@ extern "C" {
DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED
};
- /* Data persistence levels */
+ /** Data persistence levels */
typedef enum {
DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */
DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */
DM_PERSIST_VOLATILE /* Data does not survive resets */
} dm_persitence_t;
- /* The reason for the last reset */
+ /** The reason for the last reset */
typedef enum {
DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
DM_INIT_REASON_IN_FLIGHT, /* Data survives in-flight resets only */
DM_INIT_REASON_VOLATILE /* Data does not survive reset */
} dm_reset_reason;
- /* Maximum size in bytes of a single item instance */
+ /** Maximum size in bytes of a single item instance */
#define DM_MAX_DATA_SIZE 124
- /* Retrieve from the data manager store */
+ /** Retrieve from the data manager store */
__EXPORT ssize_t
dm_read(
dm_item_t item, /* The item type to retrieve */
@@ -91,7 +91,7 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
- /* write to the data manager store */
+ /** write to the data manager store */
__EXPORT ssize_t
dm_write(
dm_item_t item, /* The item type to store */
@@ -101,13 +101,13 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
- /* Erase all items of this type */
+ /** Erase all items of this type */
__EXPORT int
dm_clear(
dm_item_t item /* The item type to clear */
);
- /* Tell the data manager about the type of the last reset */
+ /** Tell the data manager about the type of the last reset */
__EXPORT int
dm_restart(
dm_reset_reason restart_type /* The last reset type */
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
index 27670dd3f..234607b3d 100644
--- a/src/modules/dataman/module.mk
+++ b/src/modules/dataman/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = dataman
SRCS = dataman.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index dadcc1dce..25272051b 100644
--- a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_main.cpp
+ * @file ekf_att_pos_estimator_main.cpp
* Implementation of the attitude and position estimator.
*
* @author Paul Riseborough <p_riseborough@live.com.au>
@@ -97,6 +97,7 @@ __EXPORT uint32_t millis();
static uint64_t last_run = 0;
static uint64_t IMUmsec = 0;
+static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000;
uint32_t millis()
{
@@ -194,6 +195,7 @@ private:
bool _baro_init;
bool _gps_initialized;
uint64_t _gps_start_time;
+ uint64_t _filter_start_time;
bool _gyro_valid;
bool _accel_valid;
bool _mag_valid;
@@ -246,7 +248,7 @@ private:
float _velocity_xy_filtered;
float _velocity_z_filtered;
- float _airspeed_filtered;
+ float _airspeed_filtered;
/**
* Update our local parameter cache.
@@ -272,7 +274,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace estimator
@@ -306,6 +308,8 @@ FixedwingEstimator::FixedwingEstimator() :
_vstatus_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
+ _mission_sub(-1),
+ _home_sub(-1),
/* publications */
_att_pub(-1),
@@ -336,13 +340,13 @@ FixedwingEstimator::FixedwingEstimator() :
_baro_gps_offset(0.0f),
/* performance counters */
- _loop_perf(perf_alloc(PC_COUNT, "fw_att_pos_estimator")),
- _perf_gyro(perf_alloc(PC_COUNT, "fw_ekf_gyro_upd")),
- _perf_accel(perf_alloc(PC_COUNT, "fw_ekf_accel_upd")),
- _perf_mag(perf_alloc(PC_COUNT, "fw_ekf_mag_upd")),
- _perf_gps(perf_alloc(PC_COUNT, "fw_ekf_gps_upd")),
- _perf_baro(perf_alloc(PC_COUNT, "fw_ekf_baro_upd")),
- _perf_airspeed(perf_alloc(PC_COUNT, "fw_ekf_aspd_upd")),
+ _loop_perf(perf_alloc(PC_COUNT, "ekf_att_pos_estimator")),
+ _perf_gyro(perf_alloc(PC_COUNT, "ekf_att_pos_gyro_upd")),
+ _perf_accel(perf_alloc(PC_COUNT, "ekf_att_pos_accel_upd")),
+ _perf_mag(perf_alloc(PC_COUNT, "ekf_att_pos_mag_upd")),
+ _perf_gps(perf_alloc(PC_COUNT, "ekf_att_pos_gps_upd")),
+ _perf_baro(perf_alloc(PC_COUNT, "ekf_att_pos_baro_upd")),
+ _perf_airspeed(perf_alloc(PC_COUNT, "ekf_att_pos_aspd_upd")),
/* states */
_initialized(false),
@@ -509,14 +513,14 @@ FixedwingEstimator::task_main_trampoline(int argc, char *argv[])
estimator::g_estimator->task_main();
}
-float dt = 0.0f; // time lapsed since last covariance prediction
-
void
FixedwingEstimator::task_main()
{
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
_ekf = new AttPosEKF();
+ float dt = 0.0f; // time lapsed since last covariance prediction
+ _filter_start_time = hrt_absolute_time();
if (!_ekf) {
errx(1, "failed allocating EKF filter - out of RAM!");
@@ -642,6 +646,7 @@ FixedwingEstimator::task_main()
_ekf->ZeroVariables();
_ekf->dtIMU = 0.01f;
+ _filter_start_time = last_sensor_timestamp;
/* now skip this loop and get data on the next one, which will also re-init the filter */
continue;
@@ -719,6 +724,8 @@ FixedwingEstimator::task_main()
if (last_accel != _sensor_combined.accelerometer_timestamp) {
accel_updated = true;
+ } else {
+ accel_updated = false;
}
last_accel = _sensor_combined.accelerometer_timestamp;
@@ -809,7 +816,6 @@ FixedwingEstimator::task_main()
perf_count(_perf_gps);
if (_gps.fix_type < 3) {
- gps_updated = false;
newDataGps = false;
} else {
@@ -1025,7 +1031,7 @@ FixedwingEstimator::task_main()
* PART TWO: EXECUTE THE FILTER
**/
- if (_baro_init && _gyro_valid && _accel_valid && _mag_valid) {
+ if ((hrt_elapsed_time(&_filter_start_time) > FILTER_INIT_DELAY) && _baro_init && _gyro_valid && _accel_valid && _mag_valid) {
float initVelNED[3];
@@ -1042,9 +1048,9 @@ FixedwingEstimator::task_main()
// Set up height correctly
orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
- _baro_gps_offset = gps_alt - _baro.altitude;
+ _baro_gps_offset = _baro_ref - _baro.altitude;
_ekf->baroHgt = _baro.altitude;
- _ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref);
+ _ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref));
// Set up position variables correctly
_ekf->GPSstatus = _gps.fix_type;
@@ -1061,14 +1067,14 @@ FixedwingEstimator::task_main()
// Initialize projection
_local_pos.ref_lat = lat;
_local_pos.ref_lon = lon;
- _local_pos.ref_alt = _baro_ref + _baro_gps_offset;
+ _local_pos.ref_alt = gps_alt;
_local_pos.ref_timestamp = _gps.timestamp_position;
map_projection_init(&_pos_ref, lat, lon);
mavlink_log_info(_mavlink_fd, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt);
warnx("HOME/REF: LA %8.4f,LO %8.4f,ALT %8.2f V: %8.4f %8.4f %8.4f", lat, lon, (double)gps_alt,
(double)_ekf->velNED[0], (double)_ekf->velNED[1], (double)_ekf->velNED[2]);
- warnx("BARO: %8.4f m / ref: %8.4f m", _ekf->baroHgt, _ekf->hgtMea);
+ warnx("BARO: %8.4f m / ref: %8.4f m / gps offs: %8.4f m", (double)_ekf->baroHgt, (double)_baro_ref, (double)_baro_gps_offset);
warnx("GPS: eph: %8.4f, epv: %8.4f, declination: %8.4f", (double)_gps.eph, (double)_gps.epv, (double)math::degrees(declination));
_gps_initialized = true;
@@ -1084,6 +1090,10 @@ FixedwingEstimator::task_main()
_ekf->posNE[0] = _ekf->posNED[0];
_ekf->posNE[1] = _ekf->posNED[1];
+
+ _local_pos.ref_alt = _baro_ref;
+ _baro_gps_offset = 0.0f;
+
_ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f);
}
}
@@ -1263,7 +1273,8 @@ FixedwingEstimator::task_main()
_local_pos.timestamp = last_sensor_timestamp;
_local_pos.x = _ekf->states[7];
_local_pos.y = _ekf->states[8];
- _local_pos.z = _ekf->states[9] + _baro_gps_offset;
+ // XXX need to announce change of Z reference somehow elegantly
+ _local_pos.z = _ekf->states[9] - _baro_gps_offset;
_local_pos.vx = _ekf->states[4];
_local_pos.vy = _ekf->states[5];
@@ -1324,8 +1335,8 @@ FixedwingEstimator::task_main()
_global_pos.vel_e = 0.0f;
}
- /* local pos alt is negative, change sign and add alt offset */
- _global_pos.alt = _local_pos.ref_alt + (-_local_pos.z);
+ /* local pos alt is negative, change sign and add alt offsets */
+ _global_pos.alt = _local_pos.ref_alt + _baro_gps_offset + (-_local_pos.z);
if (_local_pos.v_z_valid) {
_global_pos.vel_d = _local_pos.vz;
@@ -1400,7 +1411,8 @@ FixedwingEstimator::print_status()
// 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
// 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
- printf("dtIMU: %8.6f dt: %8.6f IMUmsec: %d\n", (double)_ekf->dtIMU, (double)dt, (int)IMUmsec);
+ printf("dtIMU: %8.6f IMUmsec: %d\n", (double)_ekf->dtIMU, (int)IMUmsec);
+ printf("ref alt: %8.6f\n", (double)_local_pos.ref_alt);
printf("dvel: %8.6f %8.6f %8.6f accel: %8.6f %8.6f %8.6f\n", (double)_ekf->dVelIMU.x, (double)_ekf->dVelIMU.y, (double)_ekf->dVelIMU.z, (double)_ekf->accel.x, (double)_ekf->accel.y, (double)_ekf->accel.z);
printf("dang: %8.4f %8.4f %8.4f dang corr: %8.4f %8.4f %8.4f\n" , (double)_ekf->dAngIMU.x, (double)_ekf->dAngIMU.y, (double)_ekf->dAngIMU.z, (double)_ekf->correctedDelAng.x, (double)_ekf->correctedDelAng.y, (double)_ekf->correctedDelAng.z);
printf("states (quat) [1-4]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[0], (double)_ekf->states[1], (double)_ekf->states[2], (double)_ekf->states[3]);
diff --git a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
index d2c6e1f15..8c82dd6c1 100644
--- a/src/modules/ekf_att_pos_estimator/fw_att_pos_estimator_params.c
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_params.c
+ * @file ekf_att_pos_estimator_params.c
*
* Parameters defined by the attitude and position estimator task
*
@@ -226,11 +226,11 @@ PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
* Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f.
* Increasing this value makes the bias estimation faster and noisier.
*
- * @min 0.0001
+ * @min 0.00001
* @max 0.001
* @group Position Estimator
*/
-PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.0001f);
+PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.00005f);
/**
* Magnetometer earth frame offsets process noise
diff --git a/src/modules/ekf_att_pos_estimator/estimator.cpp b/src/modules/ekf_att_pos_estimator/estimator.cpp
index a6d6a9db5..23ecd89ac 100644
--- a/src/modules/ekf_att_pos_estimator/estimator.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator.cpp
@@ -1,5 +1,6 @@
#include "estimator.h"
#include <string.h>
+#include <stdarg.h>
// Define EKF_DEBUG here to enable the debug print calls
// if the macro is not set, these will be completely
@@ -1268,7 +1269,7 @@ void AttPosEKF::FuseMagnetometer()
for (uint8_t i = 0; i < n_states; i++) {
H_MAG[i] = 0.0f;
}
- uint8_t indexLimit;
+ unsigned indexLimit;
// Perform sequential fusion of Magnetometer measurements.
// This assumes that the errors in the different components are
@@ -1281,11 +1282,11 @@ void AttPosEKF::FuseMagnetometer()
// Limit range of states modified when on ground
if(!onGround)
{
- indexLimit = 22;
+ indexLimit = n_states;
}
else
{
- indexLimit = 13;
+ indexLimit = 13 + 1;
}
// Sequential fusion of XYZ components to spread processing load across
@@ -1346,7 +1347,16 @@ void AttPosEKF::FuseMagnetometer()
H_MAG[19] = 1.0f;
// Calculate Kalman gain
- SK_MX[0] = 1/(P[19][19] + R_MAG + P[1][19]*SH_MAG[0] + P[3][19]*SH_MAG[2] - P[16][19]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) - (2*magD*q0 - 2*magE*q1 + 2*magN*q2)*(P[19][2] + P[1][2]*SH_MAG[0] + P[3][2]*SH_MAG[2] - P[16][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][2]*(2*q0*q3 + 2*q1*q2) - P[18][2]*(2*q0*q2 - 2*q1*q3) - P[2][2]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][0] + P[1][0]*SH_MAG[0] + P[3][0]*SH_MAG[2] - P[16][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][0]*(2*q0*q3 + 2*q1*q2) - P[18][0]*(2*q0*q2 - 2*q1*q3) - P[2][0]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[19][1] + P[1][1]*SH_MAG[0] + P[3][1]*SH_MAG[2] - P[16][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][1]*(2*q0*q3 + 2*q1*q2) - P[18][1]*(2*q0*q2 - 2*q1*q3) - P[2][1]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[19][3] + P[1][3]*SH_MAG[0] + P[3][3]*SH_MAG[2] - P[16][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][3]*(2*q0*q3 + 2*q1*q2) - P[18][3]*(2*q0*q2 - 2*q1*q3) - P[2][3]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[1][16]*SH_MAG[0] + P[3][16]*SH_MAG[2] - P[16][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][16]*(2*q0*q3 + 2*q1*q2) - P[18][16]*(2*q0*q2 - 2*q1*q3) - P[2][16]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[17][19]*(2*q0*q3 + 2*q1*q2) - P[18][19]*(2*q0*q2 - 2*q1*q3) - P[2][19]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + (2*q0*q3 + 2*q1*q2)*(P[19][17] + P[1][17]*SH_MAG[0] + P[3][17]*SH_MAG[2] - P[16][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][17]*(2*q0*q3 + 2*q1*q2) - P[18][17]*(2*q0*q2 - 2*q1*q3) - P[2][17]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[19][18] + P[1][18]*SH_MAG[0] + P[3][18]*SH_MAG[2] - P[16][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][18]*(2*q0*q3 + 2*q1*q2) - P[18][18]*(2*q0*q2 - 2*q1*q3) - P[2][18]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ float temp = (P[19][19] + R_MAG + P[1][19]*SH_MAG[0] + P[3][19]*SH_MAG[2] - P[16][19]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) - (2*magD*q0 - 2*magE*q1 + 2*magN*q2)*(P[19][2] + P[1][2]*SH_MAG[0] + P[3][2]*SH_MAG[2] - P[16][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][2]*(2*q0*q3 + 2*q1*q2) - P[18][2]*(2*q0*q2 - 2*q1*q3) - P[2][2]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][0] + P[1][0]*SH_MAG[0] + P[3][0]*SH_MAG[2] - P[16][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][0]*(2*q0*q3 + 2*q1*q2) - P[18][0]*(2*q0*q2 - 2*q1*q3) - P[2][0]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[19][1] + P[1][1]*SH_MAG[0] + P[3][1]*SH_MAG[2] - P[16][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][1]*(2*q0*q3 + 2*q1*q2) - P[18][1]*(2*q0*q2 - 2*q1*q3) - P[2][1]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[19][3] + P[1][3]*SH_MAG[0] + P[3][3]*SH_MAG[2] - P[16][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][3]*(2*q0*q3 + 2*q1*q2) - P[18][3]*(2*q0*q2 - 2*q1*q3) - P[2][3]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[1][16]*SH_MAG[0] + P[3][16]*SH_MAG[2] - P[16][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][16]*(2*q0*q3 + 2*q1*q2) - P[18][16]*(2*q0*q2 - 2*q1*q3) - P[2][16]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[17][19]*(2*q0*q3 + 2*q1*q2) - P[18][19]*(2*q0*q2 - 2*q1*q3) - P[2][19]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + (2*q0*q3 + 2*q1*q2)*(P[19][17] + P[1][17]*SH_MAG[0] + P[3][17]*SH_MAG[2] - P[16][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][17]*(2*q0*q3 + 2*q1*q2) - P[18][17]*(2*q0*q2 - 2*q1*q3) - P[2][17]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[19][18] + P[1][18]*SH_MAG[0] + P[3][18]*SH_MAG[2] - P[16][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][18]*(2*q0*q3 + 2*q1*q2) - P[18][18]*(2*q0*q2 - 2*q1*q3) - P[2][18]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MX[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[19][19] += 0.1f*R_MAG;
+ obsIndex = 1;
+ return;
+ }
SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6];
SK_MX[2] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
SK_MX[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
@@ -1398,7 +1408,16 @@ void AttPosEKF::FuseMagnetometer()
H_MAG[20] = 1;
// Calculate Kalman gain
- SK_MY[0] = 1/(P[20][20] + R_MAG + P[0][20]*SH_MAG[2] + P[1][20]*SH_MAG[1] + P[2][20]*SH_MAG[0] - P[17][20]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[20][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[17][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][16]*(2*q0*q3 - 2*q1*q2) + P[18][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[20][18] + P[0][18]*SH_MAG[2] + P[1][18]*SH_MAG[1] + P[2][18]*SH_MAG[0] - P[17][18]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][18]*(2*q0*q3 - 2*q1*q2) + P[18][18]*(2*q0*q1 + 2*q2*q3) - P[3][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[17][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][3]*(2*q0*q3 - 2*q1*q2) + P[18][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[16][20]*(2*q0*q3 - 2*q1*q2) + P[18][20]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[20][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[17][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][0]*(2*q0*q3 - 2*q1*q2) + P[18][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[17][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][1]*(2*q0*q3 - 2*q1*q2) + P[18][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[17][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][2]*(2*q0*q3 - 2*q1*q2) + P[18][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[17][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][17]*(2*q0*q3 - 2*q1*q2) + P[18][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ float temp = (P[20][20] + R_MAG + P[0][20]*SH_MAG[2] + P[1][20]*SH_MAG[1] + P[2][20]*SH_MAG[0] - P[17][20]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[20][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[17][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][16]*(2*q0*q3 - 2*q1*q2) + P[18][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[20][18] + P[0][18]*SH_MAG[2] + P[1][18]*SH_MAG[1] + P[2][18]*SH_MAG[0] - P[17][18]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][18]*(2*q0*q3 - 2*q1*q2) + P[18][18]*(2*q0*q1 + 2*q2*q3) - P[3][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[17][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][3]*(2*q0*q3 - 2*q1*q2) + P[18][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[16][20]*(2*q0*q3 - 2*q1*q2) + P[18][20]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[20][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[17][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][0]*(2*q0*q3 - 2*q1*q2) + P[18][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[17][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][1]*(2*q0*q3 - 2*q1*q2) + P[18][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[17][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][2]*(2*q0*q3 - 2*q1*q2) + P[18][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[17][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][17]*(2*q0*q3 - 2*q1*q2) + P[18][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MY[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[20][20] += 0.1f*R_MAG;
+ obsIndex = 2;
+ return;
+ }
SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6];
SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
SK_MY[3] = 2*q0*q3 - 2*q1*q2;
@@ -1444,7 +1463,16 @@ void AttPosEKF::FuseMagnetometer()
H_MAG[21] = 1;
// Calculate Kalman gain
- SK_MZ[0] = 1/(P[21][21] + R_MAG + P[0][21]*SH_MAG[1] + P[3][21]*SH_MAG[0] + P[18][21]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) - (2*magD*q1 + 2*magE*q0 - 2*magN*q3)*(P[21][1] + P[0][1]*SH_MAG[1] + P[3][1]*SH_MAG[0] + P[18][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][1]*(2*q0*q2 + 2*q1*q3) - P[17][1]*(2*q0*q1 - 2*q2*q3) - P[1][1]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[21][2] + P[0][2]*SH_MAG[1] + P[3][2]*SH_MAG[0] + P[18][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][2]*(2*q0*q2 + 2*q1*q3) - P[17][2]*(2*q0*q1 - 2*q2*q3) - P[1][2]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[21][0] + P[0][0]*SH_MAG[1] + P[3][0]*SH_MAG[0] + P[18][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][0]*(2*q0*q2 + 2*q1*q3) - P[17][0]*(2*q0*q1 - 2*q2*q3) - P[1][0]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[21][3] + P[0][3]*SH_MAG[1] + P[3][3]*SH_MAG[0] + P[18][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][3]*(2*q0*q2 + 2*q1*q3) - P[17][3]*(2*q0*q1 - 2*q2*q3) - P[1][3]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[21][18] + P[0][18]*SH_MAG[1] + P[3][18]*SH_MAG[0] + P[18][18]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][18]*(2*q0*q2 + 2*q1*q3) - P[17][18]*(2*q0*q1 - 2*q2*q3) - P[1][18]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][21]*(2*q0*q2 + 2*q1*q3) - P[17][21]*(2*q0*q1 - 2*q2*q3) - P[1][21]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + (2*q0*q2 + 2*q1*q3)*(P[21][16] + P[0][16]*SH_MAG[1] + P[3][16]*SH_MAG[0] + P[18][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][16]*(2*q0*q2 + 2*q1*q3) - P[17][16]*(2*q0*q1 - 2*q2*q3) - P[1][16]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[21][17] + P[0][17]*SH_MAG[1] + P[3][17]*SH_MAG[0] + P[18][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][17]*(2*q0*q2 + 2*q1*q3) - P[17][17]*(2*q0*q1 - 2*q2*q3) - P[1][17]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][21]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ float temp = (P[21][21] + R_MAG + P[0][21]*SH_MAG[1] + P[3][21]*SH_MAG[0] + P[18][21]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) - (2*magD*q1 + 2*magE*q0 - 2*magN*q3)*(P[21][1] + P[0][1]*SH_MAG[1] + P[3][1]*SH_MAG[0] + P[18][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][1]*(2*q0*q2 + 2*q1*q3) - P[17][1]*(2*q0*q1 - 2*q2*q3) - P[1][1]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[21][2] + P[0][2]*SH_MAG[1] + P[3][2]*SH_MAG[0] + P[18][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][2]*(2*q0*q2 + 2*q1*q3) - P[17][2]*(2*q0*q1 - 2*q2*q3) - P[1][2]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[21][0] + P[0][0]*SH_MAG[1] + P[3][0]*SH_MAG[0] + P[18][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][0]*(2*q0*q2 + 2*q1*q3) - P[17][0]*(2*q0*q1 - 2*q2*q3) - P[1][0]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[21][3] + P[0][3]*SH_MAG[1] + P[3][3]*SH_MAG[0] + P[18][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][3]*(2*q0*q2 + 2*q1*q3) - P[17][3]*(2*q0*q1 - 2*q2*q3) - P[1][3]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[21][18] + P[0][18]*SH_MAG[1] + P[3][18]*SH_MAG[0] + P[18][18]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][18]*(2*q0*q2 + 2*q1*q3) - P[17][18]*(2*q0*q1 - 2*q2*q3) - P[1][18]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][21]*(2*q0*q2 + 2*q1*q3) - P[17][21]*(2*q0*q1 - 2*q2*q3) - P[1][21]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + (2*q0*q2 + 2*q1*q3)*(P[21][16] + P[0][16]*SH_MAG[1] + P[3][16]*SH_MAG[0] + P[18][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][16]*(2*q0*q2 + 2*q1*q3) - P[17][16]*(2*q0*q1 - 2*q2*q3) - P[1][16]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[21][17] + P[0][17]*SH_MAG[1] + P[3][17]*SH_MAG[0] + P[18][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][17]*(2*q0*q2 + 2*q1*q3) - P[17][17]*(2*q0*q1 - 2*q2*q3) - P[1][17]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][21]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MZ[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[21][21] += 0.1f*R_MAG;
+ obsIndex = 3;
+ return;
+ }
SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
SK_MZ[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
SK_MZ[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
@@ -1483,7 +1511,7 @@ void AttPosEKF::FuseMagnetometer()
if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0)
{
// correct the state vector
- for (uint8_t j= 0; j<=indexLimit; j++)
+ for (uint8_t j= 0; j < indexLimit; j++)
{
states[j] = states[j] - Kfusion[j] * innovMag[obsIndex];
}
@@ -1500,7 +1528,7 @@ void AttPosEKF::FuseMagnetometer()
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in KH to reduce the
// number of operations
- for (uint8_t i = 0; i<=indexLimit; i++)
+ for (uint8_t i = 0; i < indexLimit; i++)
{
for (uint8_t j = 0; j <= 3; j++)
{
@@ -1522,9 +1550,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i<=indexLimit; i++)
+ for (uint8_t i = 0; i < indexLimit; i++)
{
- for (uint8_t j = 0; j<=indexLimit; j++)
+ for (uint8_t j = 0; j < indexLimit; j++)
{
KHP[i][j] = 0.0f;
for (uint8_t k = 0; k <= 3; k++)
@@ -1541,9 +1569,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i <= indexLimit; i++)
+ for (uint8_t i = 0; i < indexLimit; i++)
{
- for (uint8_t j = 0; j <= indexLimit; j++)
+ for (uint8_t j = 0; j < indexLimit; j++)
{
P[i][j] = P[i][j] - KHP[i][j];
}
@@ -1564,6 +1592,7 @@ void AttPosEKF::FuseAirspeed()
float vwe;
float R_TAS = sq(airspeedMeasurementSigma);
float SH_TAS[3];
+ float SK_TAS;
float VtasPred;
// Copy required states to local variable names
@@ -1593,7 +1622,16 @@ void AttPosEKF::FuseAirspeed()
H_TAS[15] = -SH_TAS[1];
// Calculate Kalman gains
- float SK_TAS = 1/(R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[14][4]*SH_TAS[2] - P[15][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[14][5]*SH_TAS[2] - P[15][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][14]*SH_TAS[2] + P[5][14]*SH_TAS[1] - P[14][14]*SH_TAS[2] - P[15][14]*SH_TAS[1] + P[6][14]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][15]*SH_TAS[2] + P[5][15]*SH_TAS[1] - P[14][15]*SH_TAS[2] - P[15][15]*SH_TAS[1] + P[6][15]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[14][6]*SH_TAS[2] - P[15][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
+ float temp = (R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[14][4]*SH_TAS[2] - P[15][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[14][5]*SH_TAS[2] - P[15][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][14]*SH_TAS[2] + P[5][14]*SH_TAS[1] - P[14][14]*SH_TAS[2] - P[15][14]*SH_TAS[1] + P[6][14]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][15]*SH_TAS[2] + P[5][15]*SH_TAS[1] - P[14][15]*SH_TAS[2] - P[15][15]*SH_TAS[1] + P[6][15]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[14][6]*SH_TAS[2] - P[15][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
+ if (temp >= R_TAS) {
+ SK_TAS = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the wind state variances and try again next time
+ P[14][14] += 0.05f*R_TAS;
+ P[15][15] += 0.05f*R_TAS;
+ return;
+ }
Kfusion[0] = SK_TAS*(P[0][4]*SH_TAS[2] - P[0][14]*SH_TAS[2] + P[0][5]*SH_TAS[1] - P[0][15]*SH_TAS[1] + P[0][6]*vd*SH_TAS[0]);
Kfusion[1] = SK_TAS*(P[1][4]*SH_TAS[2] - P[1][14]*SH_TAS[2] + P[1][5]*SH_TAS[1] - P[1][15]*SH_TAS[1] + P[1][6]*vd*SH_TAS[0]);
Kfusion[2] = SK_TAS*(P[2][4]*SH_TAS[2] - P[2][14]*SH_TAS[2] + P[2][5]*SH_TAS[1] - P[2][15]*SH_TAS[1] + P[2][6]*vd*SH_TAS[0]);
@@ -2001,7 +2039,22 @@ void AttPosEKF::CovarianceInit()
float AttPosEKF::ConstrainFloat(float val, float min, float max)
{
- return (val > max) ? max : ((val < min) ? min : val);
+ float ret;
+ if (val > max) {
+ ret = max;
+ ekf_debug("> max: %8.4f, val: %8.4f", max, val);
+ } else if (val < min) {
+ ret = min;
+ ekf_debug("< min: %8.4f, val: %8.4f", min, val);
+ } else {
+ ret = val;
+ }
+
+ if (!isfinite(val)) {
+ ekf_debug("constrain: non-finite!");
+ }
+
+ return ret;
}
void AttPosEKF::ConstrainVariances()
@@ -2466,12 +2519,18 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
void AttPosEKF::InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination)
{
- //store initial lat,long and height
+ // store initial lat,long and height
latRef = referenceLat;
lonRef = referenceLon;
hgtRef = referenceHgt;
refSet = true;
+ // we are at reference altitude, so measurement must be zero
+ hgtMea = 0.0f;
+
+ // the baro offset must be this difference now
+ baroHgtOffset = baroHgt - referenceHgt;
+
memset(&last_ekf_error, 0, sizeof(last_ekf_error));
InitializeDynamic(initvelNED, declination);
diff --git a/src/modules/ekf_att_pos_estimator/estimator.h b/src/modules/ekf_att_pos_estimator/estimator.h
index 378107b69..e821089f2 100644
--- a/src/modules/ekf_att_pos_estimator/estimator.h
+++ b/src/modules/ekf_att_pos_estimator/estimator.h
@@ -198,6 +198,7 @@ public:
float velNED[3]; // North, East, Down velocity obs (m/s)
float posNE[2]; // North, East position obs (m)
float hgtMea; // measured height (m)
+ float baroHgtOffset; ///< the baro (weather) offset from normalized altitude
float rngMea; // Ground distance
float posNED[3]; // North, East Down position (m)
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 30955d0dd..6fefec2c2 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -32,11 +32,11 @@
############################################################################
#
-# Main Attitude and Position Estimator for Fixed Wing Aircraft
+# Main EKF Attitude and Position Estimator
#
MODULE_COMMAND = ekf_att_pos_estimator
-SRCS = fw_att_pos_estimator_main.cpp \
- fw_att_pos_estimator_params.c \
+SRCS = ekf_att_pos_estimator_main.cpp \
+ ekf_att_pos_estimator_params.c \
estimator.cpp
diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index cfae07275..bbb39f20f 100644
--- a/src/modules/fixedwing_backside/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -229,8 +229,8 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[CH_RDR] = _manual.yaw;
_actuators.control[CH_THR] = _manual.throttle;
- } else if (_status.main_state == MAIN_STATE_SEATBELT ||
- _status.main_state == MAIN_STATE_EASY /* TODO, implement easy */) {
+ } else if (_status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL /* TODO, implement pos control */) {
// calculate velocity, XXX should be airspeed, but using ground speed for now
// for the purpose of control we will limit the velocity feedback between
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index 81bef0db3..178b590ae 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -134,6 +134,8 @@ private:
struct vehicle_global_position_s _global_pos; /**< global position */
perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
+ perf_counter_t _nonfinite_output_perf; /**< performance counter for non finite output */
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
@@ -273,7 +275,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace att_control
@@ -304,12 +306,14 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
/* publications */
_rate_sp_pub(-1),
- _actuators_0_pub(-1),
_attitude_sp_pub(-1),
+ _actuators_0_pub(-1),
_actuators_1_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
+ _nonfinite_output_perf(perf_alloc(PC_COUNT, "fw att control nonfinite output")),
/* states */
_setpoint_valid(false)
{
@@ -387,6 +391,10 @@ FixedwingAttitudeControl::~FixedwingAttitudeControl()
} while (_control_task != -1);
}
+ perf_free(_loop_perf);
+ perf_free(_nonfinite_input_perf);
+ perf_free(_nonfinite_output_perf);
+
att_control::g_control = nullptr;
}
@@ -592,6 +600,8 @@ FixedwingAttitudeControl::task_main()
while (!_task_should_exit) {
+ static int loop_counter = 0;
+
/* wait for up to 500ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
@@ -672,10 +682,12 @@ FixedwingAttitudeControl::task_main()
float airspeed;
/* if airspeed is not updating, we assume the normal average speed */
- if (!isfinite(_airspeed.true_airspeed_m_s) ||
+ if (bool nonfinite = !isfinite(_airspeed.true_airspeed_m_s) ||
hrt_elapsed_time(&_airspeed.timestamp) > 1e6) {
airspeed = _parameters.airspeed_trim;
-
+ if (nonfinite) {
+ perf_count(_nonfinite_input_perf);
+ }
} else {
airspeed = _airspeed.true_airspeed_m_s;
}
@@ -706,20 +718,21 @@ FixedwingAttitudeControl::task_main()
} else {
/*
* Scale down roll and pitch as the setpoints are radians
- * and a typical remote can only do 45 degrees, the mapping is
- * -1..+1 to -45..+45 degrees or -0.75..+0.75 radians.
+ * and a typical remote can only do around 45 degrees, the mapping is
+ * -1..+1 to -man_roll_max rad..+man_roll_max rad (equivalent for pitch)
*
* With this mapping the stick angle is a 1:1 representation of
- * the commanded attitude. If more than 45 degrees are desired,
- * a scaling parameter can be applied to the remote.
+ * the commanded attitude.
*
* The trim gets subtracted here from the manual setpoint to get
* the intended attitude setpoint. Later, after the rate control step the
* trim is added again to the control signal.
*/
- roll_sp = (_manual.roll * _parameters.man_roll_max - _parameters.trim_roll) + _parameters.rollsp_offset_rad;
- pitch_sp = (-_manual.pitch * _parameters.man_pitch_max - _parameters.trim_pitch) + _parameters.pitchsp_offset_rad;
- throttle_sp = _manual.throttle;
+ roll_sp = (_manual.y * _parameters.man_roll_max - _parameters.trim_roll)
+ + _parameters.rollsp_offset_rad;
+ pitch_sp = -(_manual.x * _parameters.man_pitch_max - _parameters.trim_pitch)
+ + _parameters.pitchsp_offset_rad;
+ throttle_sp = _manual.z;
_actuators.control[4] = _manual.flaps;
/*
@@ -754,7 +767,9 @@ FixedwingAttitudeControl::task_main()
speed_body_v = _att.R[0][1] * _global_pos.vel_n + _att.R[1][1] * _global_pos.vel_e + _att.R[2][1] * _global_pos.vel_d;
speed_body_w = _att.R[0][2] * _global_pos.vel_n + _att.R[1][2] * _global_pos.vel_e + _att.R[2][2] * _global_pos.vel_d;
} else {
- warnx("Did not get a valid R\n");
+ if (loop_counter % 10 == 0) {
+ warnx("Did not get a valid R\n");
+ }
}
/* Run attitude controllers */
@@ -772,7 +787,12 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[0] = (isfinite(roll_u)) ? roll_u + _parameters.trim_roll : _parameters.trim_roll;
if (!isfinite(roll_u)) {
- warnx("roll_u %.4f", roll_u);
+ _roll_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+
+ if (loop_counter % 10 == 0) {
+ warnx("roll_u %.4f", (double)roll_u);
+ }
}
float pitch_u = _pitch_ctrl.control_bodyrate(_att.roll, _att.pitch,
@@ -781,8 +801,22 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[1] = (isfinite(pitch_u)) ? pitch_u + _parameters.trim_pitch : _parameters.trim_pitch;
if (!isfinite(pitch_u)) {
- warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f, airspeed %.4f, airspeed_scaling %.4f, roll_sp %.4f, pitch_sp %.4f, _roll_ctrl.get_desired_rate() %.4f, _pitch_ctrl.get_desired_rate() %.4f att_sp.roll_body %.4f",
- (double)pitch_u, (double)_yaw_ctrl.get_desired_rate(), (double)airspeed, (double)airspeed_scaling, (double)roll_sp, (double)pitch_sp, (double)_roll_ctrl.get_desired_rate(), (double)_pitch_ctrl.get_desired_rate(), (double)_att_sp.roll_body);
+ _pitch_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f,"
+ " airspeed %.4f, airspeed_scaling %.4f,"
+ " roll_sp %.4f, pitch_sp %.4f,"
+ " _roll_ctrl.get_desired_rate() %.4f,"
+ " _pitch_ctrl.get_desired_rate() %.4f"
+ " att_sp.roll_body %.4f",
+ (double)pitch_u, (double)_yaw_ctrl.get_desired_rate(),
+ (double)airspeed, (double)airspeed_scaling,
+ (double)roll_sp, (double)pitch_sp,
+ (double)_roll_ctrl.get_desired_rate(),
+ (double)_pitch_ctrl.get_desired_rate(),
+ (double)_att_sp.roll_body);
+ }
}
float yaw_u = _yaw_ctrl.control_bodyrate(_att.roll, _att.pitch,
@@ -791,16 +825,25 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw;
if (!isfinite(yaw_u)) {
- warnx("yaw_u %.4f", (double)yaw_u);
+ _yaw_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("yaw_u %.4f", (double)yaw_u);
+ }
}
/* throttle passed through */
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
if (!isfinite(throttle_sp)) {
- warnx("throttle_sp %.4f", (double)throttle_sp);
+ if (loop_counter % 10 == 0) {
+ warnx("throttle_sp %.4f", (double)throttle_sp);
+ }
}
} else {
- warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp);
+ perf_count(_nonfinite_input_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp);
+ }
}
/*
@@ -825,10 +868,10 @@ FixedwingAttitudeControl::task_main()
} else {
/* manual/direct control */
- _actuators.control[0] = _manual.roll;
- _actuators.control[1] = -_manual.pitch;
- _actuators.control[2] = _manual.yaw;
- _actuators.control[3] = _manual.throttle;
+ _actuators.control[0] = _manual.y;
+ _actuators.control[1] = -_manual.x;
+ _actuators.control[2] = _manual.r;
+ _actuators.control[3] = _manual.z;
_actuators.control[4] = _manual.flaps;
}
@@ -864,6 +907,7 @@ FixedwingAttitudeControl::task_main()
}
+ loop_counter++;
perf_end(_loop_perf);
}
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index a00a388a8..a53118dec 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -89,6 +89,7 @@
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
+#include <drivers/drv_range_finder.h>
#include "landingslope.h"
@@ -134,6 +135,7 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _sensor_combined_sub; /**< for body frame accelerations */
+ int _range_finder_sub; /**< range finder subscription */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */
@@ -147,11 +149,12 @@ private:
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
+ struct range_finder_report _range_finder; /**< range finder report */
perf_counter_t _loop_perf; /**< loop performance counter */
/** manual control states */
- float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
+ float _altctrl_hold_heading; /**< heading the system should hold in altctrl mode */
double _loiter_hold_lat;
double _loiter_hold_lon;
float _loiter_hold_alt;
@@ -179,7 +182,7 @@ private:
/* Landingslope object */
Landingslope landingslope;
- float flare_curve_alt_last;
+ float flare_curve_alt_rel_last;
/* heading hold */
float target_bearing;
@@ -237,6 +240,7 @@ private:
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
+ float range_finder_rel_alt;
} _parameters; /**< local copies of interesting parameters */
@@ -281,6 +285,7 @@ private:
param_t land_flare_alt_relative;
param_t land_thrust_lim_alt_relative;
param_t land_heading_hold_horizontal_distance;
+ param_t range_finder_rel_alt;
} _parameter_handles; /**< handles for interesting parameters */
@@ -307,6 +312,12 @@ private:
bool vehicle_airspeed_poll();
/**
+ * Check for range finder updates.
+ */
+ bool range_finder_poll();
+
+
+ /**
* Check for position updates.
*/
void vehicle_attitude_poll();
@@ -327,6 +338,11 @@ private:
void navigation_capabilities_publish();
/**
+ * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ */
+ float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+
+ /**
* Control position.
*/
bool control_position(const math::Vector<2> &global_pos, const math::Vector<2> &ground_speed,
@@ -343,7 +359,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
/*
* Reset takeoff state
@@ -382,6 +398,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_control_mode_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
+ _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
@@ -398,9 +415,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
land_motor_lim(false),
land_onslope(false),
launch_detected(false),
- last_manual(false),
usePreTakeoffThrust(false),
- flare_curve_alt_last(0.0f),
+ last_manual(false),
+ flare_curve_alt_rel_last(0.0f),
launchDetector(),
_airspeed_error(0.0f),
_airspeed_valid(false),
@@ -414,7 +431,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
_control_mode(),
_global_pos(),
_pos_sp_triplet(),
- _sensor_combined()
+ _sensor_combined(),
+ _range_finder()
{
_nav_capabilities.turn_distance = 0.0f;
@@ -439,6 +457,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
+ _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
@@ -528,6 +547,8 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative));
param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
+ param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
+
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
@@ -623,6 +644,20 @@ FixedwingPositionControl::vehicle_airspeed_poll()
return airspeed_updated;
}
+bool
+FixedwingPositionControl::range_finder_poll()
+{
+ /* check if there is a range finder measurement */
+ bool range_finder_updated;
+ orb_check(_range_finder_sub, &range_finder_updated);
+
+ if (range_finder_updated) {
+ orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
+ }
+
+ return range_finder_updated;
+}
+
void
FixedwingPositionControl::vehicle_attitude_poll()
{
@@ -750,6 +785,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
}
}
+float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
+{
+ float rel_alt_estimated = current_alt - land_setpoint_alt;
+
+ /* only use range finder if:
+ * parameter (range_finder_use_relative_alt) > 0
+ * the measurement is valid
+ * the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
+ */
+ if (range_finder_use_relative_alt < 0 || !range_finder.valid || rel_alt_estimated > range_finder_use_relative_alt ) {
+ return rel_alt_estimated;
+ }
+
+ return range_finder.distance;
+
+}
+
bool
FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed,
const struct position_setpoint_triplet_s &pos_sp_triplet)
@@ -892,12 +944,14 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
- float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt);
+ float L_altitude_rel = landingslope.getLandingSlopeRelativeAltitude(L_wp_distance);
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
- float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
+
+ float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
- if ( (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
+ if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
@@ -907,7 +961,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
if (!land_motor_lim) {
land_motor_lim = true;
@@ -916,16 +970,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
- float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float flare_curve_alt_rel = landingslope.getFlareCurveRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
/* avoid climbout */
- if ((flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical) || land_stayonground)
+ if ((flare_curve_alt_rel_last < flare_curve_alt_rel && land_noreturn_vertical) || land_stayonground)
{
- flare_curve_alt = pos_sp_triplet.current.alt;
+ flare_curve_alt_rel = 0.0f; // stay on ground
land_stayonground = true;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, flare_curve_alt, calculate_target_airspeed(airspeed_land),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + flare_curve_alt_rel, calculate_target_airspeed(airspeed_land),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, flare_pitch_angle_rad,
0.0f, throttle_max, throttle_land,
@@ -937,7 +991,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
//warnx("Landing: flare, _global_pos.alt %.1f, flare_curve_alt %.1f, flare_curve_alt_last %.1f, flare_length %.1f, wp_distance %.1f", _global_pos.alt, flare_curve_alt, flare_curve_alt_last, flare_length, wp_distance);
- flare_curve_alt_last = flare_curve_alt;
+ flare_curve_alt_rel_last = flare_curve_alt_rel;
} else {
/* intersect glide slope:
@@ -945,20 +999,20 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
* if current position is higher or within 10m of slope follow the glide slope
* if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope
* */
- float altitude_desired = _global_pos.alt;
- if (_global_pos.alt > landing_slope_alt_desired - 10.0f) {
+ float altitude_desired_rel = relative_alt;
+ if (relative_alt > landing_slope_alt_rel_desired - 10.0f) {
/* stay on slope */
- altitude_desired = landing_slope_alt_desired;
+ altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope");
land_onslope = true;
}
} else {
/* continue horizontally */
- altitude_desired = math::max(_global_pos.alt, L_altitude);
+ altitude_desired_rel = math::max(relative_alt, L_altitude_rel);
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, altitude_desired, calculate_target_airspeed(airspeed_approach),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + altitude_desired_rel, calculate_target_airspeed(airspeed_approach),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, math::radians(_parameters.pitch_limit_min),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
@@ -1047,16 +1101,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.roll_reset_integral = true;
}
- } else if (0/* easy mode enabled */) {
+ } else if (0/* posctrl mode enabled */) {
- /** EASY FLIGHT **/
+ /** POSCTRL FLIGHT **/
- if (0/* switched from another mode to easy */) {
- _seatbelt_hold_heading = _att.yaw;
+ if (0/* switched from another mode to posctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* easy on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* posctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.r;
}
//XXX not used
@@ -1069,44 +1123,44 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// climb_out = true;
// }
- /* if in seatbelt mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
+ _manual.z;
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
false, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
_parameters.pitch_limit_min, _parameters.pitch_limit_max);
- } else if (0/* seatbelt mode enabled */) {
+ } else if (0/* altctrl mode enabled */) {
- /** SEATBELT FLIGHT **/
+ /** ALTCTRL FLIGHT **/
- if (0/* switched from another mode to seatbelt */) {
- _seatbelt_hold_heading = _att.yaw;
+ if (0/* switched from another mode to altctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* seatbelt on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* altctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.r;
}
- /* if in seatbelt mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
+ _manual.z;
/* user switched off throttle */
- if (_manual.throttle < 0.1f) {
+ if (_manual.z < 0.1f) {
throttle_max = 0.0f;
/* switch to pure pitch based altitude control, give up speed */
_tecs.set_speed_weight(0.0f);
@@ -1116,15 +1170,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
bool climb_out = false;
/* user wants to climb out */
- if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
+ if (_manual.x > 0.3f && _manual.z > 0.8f) {
climb_out = true;
}
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
- _att_sp.roll_body = _manual.roll;
- _att_sp.yaw_body = _manual.yaw;
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
+ _att_sp.roll_body = _manual.y;
+ _att_sp.yaw_body = _manual.r;
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
climb_out, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
@@ -1181,6 +1235,7 @@ FixedwingPositionControl::task_main()
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
@@ -1260,6 +1315,7 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
+ range_finder_poll();
// vehicle_baro_poll();
math::Vector<2> ground_speed(_global_pos.vel_n, _global_pos.vel_e);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 37f06dbe5..f258f77da 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -375,3 +375,14 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f);
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
+
+/**
+ * Relative altitude threshold for range finder measurements for use during landing
+ *
+ * range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
+ * set to < 0 to disable
+ * the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
+ *
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
diff --git a/src/modules/fw_pos_control_l1/landingslope.cpp b/src/modules/fw_pos_control_l1/landingslope.cpp
index e5f7023ae..8ce465fe8 100644
--- a/src/modules/fw_pos_control_l1/landingslope.cpp
+++ b/src/modules/fw_pos_control_l1/landingslope.cpp
@@ -69,26 +69,46 @@ void Landingslope::calculateSlopeValues()
_horizontal_slope_displacement = (_flare_length - _d1);
}
-float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude)
+float Landingslope::getLandingSlopeRelativeAltitude(float wp_landing_distance)
{
- return Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad);
+ return Landingslope::getLandingSlopeRelativeAltitude(wp_landing_distance, _horizontal_slope_displacement, _landing_slope_angle_rad);
}
-float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude)
+float Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp)
{
/* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
- return getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude);
+ return getLandingSlopeRelativeAltitude(wp_landing_distance);
+ else
+ return 0.0f;
+}
+
+float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude)
+{
+ return Landingslope::getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad);
+}
+
+float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude)
+{
+ /* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
+ if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
+ return getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude);
else
return wp_altitude;
}
-float Landingslope::getFlareCurveAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude)
+float Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp)
{
/* If airplane is in front of waypoint return flare curve altitude, else return waypoint altitude */
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
- return wp_landing_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt;
+ return _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt;
else
- return wp_landing_altitude;
+ return 0.0f;
+}
+
+float Landingslope::getFlareCurveAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude)
+{
+
+ return wp_landing_altitude + getFlareCurveRelativeAltitudeSave(wp_landing_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
}
diff --git a/src/modules/fw_pos_control_l1/landingslope.h b/src/modules/fw_pos_control_l1/landingslope.h
index 76d65a55f..b54fd501c 100644
--- a/src/modules/fw_pos_control_l1/landingslope.h
+++ b/src/modules/fw_pos_control_l1/landingslope.h
@@ -63,11 +63,26 @@ public:
Landingslope() {}
~Landingslope() {}
+
+ /**
+ *
+ * @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ */
+ float getLandingSlopeRelativeAltitude(float wp_landing_distance);
+
+ /**
+ *
+ * @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ * Performs check if aircraft is in front of waypoint to avoid climbout
+ */
+ float getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp);
+
+
/**
*
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
*/
- float getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude);
+ float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude);
/**
*
@@ -78,11 +93,20 @@ public:
/**
*
+ * @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ */
+ __EXPORT static float getLandingSlopeRelativeAltitude(float wp_landing_distance, float horizontal_slope_displacement, float landing_slope_angle_rad)
+ {
+ return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad); //flare_relative_alt is negative
+ }
+
+ /**
+ *
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
*/
__EXPORT static float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, float horizontal_slope_displacement, float landing_slope_angle_rad)
{
- return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad) + wp_landing_altitude; //flare_relative_alt is negative
+ return getLandingSlopeRelativeAltitude(wp_landing_distance, horizontal_slope_displacement, landing_slope_angle_rad) + wp_landing_altitude;
}
/**
@@ -95,8 +119,9 @@ public:
}
+ float getFlareCurveRelativeAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp);
- float getFlareCurveAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude);
+ float getFlareCurveAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude);
void update(float landing_slope_angle_rad,
float flare_relative_alt,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 9927b9c3a..6b45736e9 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -149,10 +149,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
instance = Mavlink::get_instance(6);
break;
#endif
- }
-
- /* no valid instance, bail */
- if (!instance) {
+ default:
return;
}
@@ -211,9 +208,9 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
static void usage(void);
Mavlink::Mavlink() :
- next(nullptr),
_device_name(DEFAULT_DEVICE_NAME),
_task_should_exit(false),
+ next(nullptr),
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
@@ -234,7 +231,6 @@ Mavlink::Mavlink() :
_subscribe_to_stream_rate(0.0f),
_flow_control_enabled(true),
_message_buffer({}),
-
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
{
@@ -736,9 +732,9 @@ int Mavlink::mavlink_pm_send_param(param_t param)
if (param == PARAM_INVALID) { return 1; }
/* buffers for param transmission */
- static char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
+ char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
float val_buf;
- static mavlink_message_t tx_msg;
+ mavlink_message_t tx_msg;
/* query parameter type */
param_type_t type = param_type(param);
@@ -1543,6 +1539,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
void
Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
{
+ uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
+
uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len);
@@ -2039,14 +2037,14 @@ Mavlink::task_main(int argc, char *argv[])
if (_subscribe_to_stream != nullptr) {
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
if (_subscribe_to_stream_rate > 0.0f) {
- warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, _subscribe_to_stream_rate);
+ warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate);
} else {
warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name);
}
} else {
- warnx("stream %s not found", _subscribe_to_stream, _device_name);
+ warnx("stream %s on device %s not found", _subscribe_to_stream, _device_name);
}
delete _subscribe_to_stream;
@@ -2213,7 +2211,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1950,
(main_t)&Mavlink::start_helper,
(const char **)argv);
@@ -2252,7 +2250,6 @@ Mavlink::stream(int argc, char *argv[])
const char *device_name = DEFAULT_DEVICE_NAME;
float rate = -1.0f;
const char *stream_name = nullptr;
- int ch;
argc -= 2;
argv += 2;
@@ -2289,7 +2286,7 @@ Mavlink::stream(int argc, char *argv[])
i++;
}
- if (!err_flag && rate >= 0.0 && stream_name != nullptr) {
+ if (!err_flag && rate >= 0.0f && stream_name != nullptr) {
Mavlink *inst = get_instance_for_device(device_name);
if (inst != nullptr) {
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 1bf51fd31..25c0da820 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -221,8 +221,6 @@ private:
int _mavlink_fd;
bool _task_running;
- perf_counter_t _loop_perf; /**< loop performance counter */
-
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
@@ -237,7 +235,6 @@ private:
orb_advert_t _mission_pub;
struct mission_s mission;
- uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
MAVLINK_MODE _mode;
uint8_t _mavlink_wpm_comp_id;
@@ -283,7 +280,7 @@ private:
pthread_mutex_t _message_buffer_mutex;
-
+ perf_counter_t _loop_perf; /**< loop performance counter */
/**
* Send one parameter.
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index ec90cf599..70087cf3e 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -125,18 +125,22 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
- } else if (status->main_state == MAIN_STATE_SEATBELT) {
+ } else if (status->main_state == MAIN_STATE_ALTCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
- } else if (status->main_state == MAIN_STATE_EASY) {
+ } else if (status->main_state == MAIN_STATE_POSCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_EASY;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
} else if (status->main_state == MAIN_STATE_AUTO) {
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+
+ } else if (status->main_state == MAIN_STATE_ACRO) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
}
} else {
@@ -1139,10 +1143,10 @@ protected:
if (manual_sub->update(t)) {
mavlink_msg_manual_control_send(_channel,
mavlink_system.sysid,
- manual->roll * 1000,
- manual->pitch * 1000,
- manual->yaw * 1000,
- manual->throttle * 1000,
+ manual->x * 1000,
+ manual->y * 1000,
+ manual->z * 1000,
+ manual->r * 1000,
0);
}
}
diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp
index d432edd2b..21d5219d3 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.cpp
+++ b/src/modules/mavlink/mavlink_orb_subscription.cpp
@@ -63,7 +63,7 @@ MavlinkOrbSubscription::~MavlinkOrbSubscription()
free(_data);
}
-const orb_id_t
+orb_id_t
MavlinkOrbSubscription::get_topic()
{
return _topic;
diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h
index 5c6543e81..8c09772c8 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.h
+++ b/src/modules/mavlink/mavlink_orb_subscription.h
@@ -63,7 +63,7 @@ public:
*/
bool is_published();
void *get_data();
- const orb_id_t get_topic();
+ orb_id_t get_topic();
private:
const orb_id_t _topic; /*< topic metadata */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 4f83c6b95..33358b7b6 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -191,7 +191,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
}
}
-
+
/* If we've received a valid message, mark the flag indicating so.
This is used in the '-w' command-line flag. */
_mavlink->set_has_received_messages(true);
@@ -438,10 +438,10 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
memset(&manual, 0, sizeof(manual));
manual.timestamp = hrt_absolute_time();
- manual.pitch = man.x / 1000.0f;
- manual.roll = man.y / 1000.0f;
- manual.yaw = man.r / 1000.0f;
- manual.throttle = man.z / 1000.0f;
+ manual.x = man.x / 1000.0f;
+ manual.y = man.y / 1000.0f;
+ manual.r = man.r / 1000.0f;
+ manual.z = man.z / 1000.0f;
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
@@ -932,6 +932,8 @@ void *MavlinkReceiver::start_helper(void *context)
rcv->receive_thread(NULL);
delete rcv;
+
+ return nullptr;
}
pthread_t
@@ -949,7 +951,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 3000);
+ pthread_attr_setstacksize(&receiveloop_attr, 2900);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp
index bb19d7e33..5ec30bd33 100644
--- a/src/modules/mavlink/mavlink_stream.cpp
+++ b/src/modules/mavlink/mavlink_stream.cpp
@@ -81,5 +81,9 @@ MavlinkStream::update(const hrt_abstime t)
/* interval expired, send message */
send(t);
_last_sent = (t / _interval) * _interval;
+
+ return 0;
}
+
+ return -1;
}
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index def40d9ad..2979d20de 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -63,9 +63,13 @@ public:
MavlinkStream *next;
MavlinkStream();
- ~MavlinkStream();
+ virtual ~MavlinkStream();
void set_interval(const unsigned int interval);
void set_channel(mavlink_channel_t channel);
+
+ /**
+ * @return 0 if updated / sent, -1 if unchanged
+ */
int update(const hrt_abstime t);
virtual MavlinkStream *new_instance() = 0;
virtual void subscribe(Mavlink *mavlink) = 0;
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index dcca11977..f532e26fe 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -48,3 +48,5 @@ SRCS += mavlink_main.cpp \
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1024
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 36d95bf06..20e016da3 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,9 +32,13 @@
****************************************************************************/
/**
- * @file mc_att_control_main.c
+ * @file mc_att_control_main.cpp
* Multicopter attitude controller.
*
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
@@ -71,7 +72,7 @@
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
-#include <mathlib/mathlib.h>
+#include <lib/mathlib/mathlib.h>
#include <lib/geo/geo.h>
/**
@@ -156,10 +157,14 @@ private:
param_t yaw_rate_i;
param_t yaw_rate_d;
param_t yaw_ff;
+ param_t yaw_rate_max;
param_t man_roll_max;
param_t man_pitch_max;
param_t man_yaw_max;
+ param_t acro_roll_max;
+ param_t acro_pitch_max;
+ param_t acro_yaw_max;
} _params_handles; /**< handles for interesting parameters */
struct {
@@ -168,10 +173,12 @@ private:
math::Vector<3> rate_i; /**< I gain for angular rate error */
math::Vector<3> rate_d; /**< D gain for angular rate error */
float yaw_ff; /**< yaw control feed-forward */
+ float yaw_rate_max; /**< max yaw rate */
float man_roll_max;
float man_pitch_max;
float man_yaw_max;
+ math::Vector<3> acro_rate_max; /**< max attitude rates in acro mode */
} _params;
/**
@@ -225,9 +232,9 @@ private:
static void task_main_trampoline(int argc, char *argv[]);
/**
- * Main sensor collection task.
+ * Main attitude control task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace mc_att_control
@@ -276,6 +283,12 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params.rate_p.zero();
_params.rate_i.zero();
_params.rate_d.zero();
+ _params.yaw_ff = 0.0f;
+ _params.yaw_rate_max = 0.0f;
+ _params.man_roll_max = 0.0f;
+ _params.man_pitch_max = 0.0f;
+ _params.man_yaw_max = 0.0f;
+ _params.acro_rate_max.zero();
_rates_prev.zero();
_rates_sp.zero();
@@ -298,10 +311,13 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params_handles.yaw_rate_i = param_find("MC_YAWRATE_I");
_params_handles.yaw_rate_d = param_find("MC_YAWRATE_D");
_params_handles.yaw_ff = param_find("MC_YAW_FF");
-
+ _params_handles.yaw_rate_max = param_find("MC_YAWRATE_MAX");
_params_handles.man_roll_max = param_find("MC_MAN_R_MAX");
_params_handles.man_pitch_max = param_find("MC_MAN_P_MAX");
_params_handles.man_yaw_max = param_find("MC_MAN_Y_MAX");
+ _params_handles.acro_roll_max = param_find("MC_ACRO_R_MAX");
+ _params_handles.acro_pitch_max = param_find("MC_ACRO_P_MAX");
+ _params_handles.acro_yaw_max = param_find("MC_ACRO_Y_MAX");
/* fetch initial parameter values */
parameters_update();
@@ -367,15 +383,24 @@ MulticopterAttitudeControl::parameters_update()
_params.rate_d(2) = v;
param_get(_params_handles.yaw_ff, &_params.yaw_ff);
+ param_get(_params_handles.yaw_rate_max, &_params.yaw_rate_max);
+ _params.yaw_rate_max = math::radians(_params.yaw_rate_max);
/* manual control scale */
param_get(_params_handles.man_roll_max, &_params.man_roll_max);
param_get(_params_handles.man_pitch_max, &_params.man_pitch_max);
param_get(_params_handles.man_yaw_max, &_params.man_yaw_max);
-
- _params.man_roll_max *= M_PI / 180.0;
- _params.man_pitch_max *= M_PI / 180.0;
- _params.man_yaw_max *= M_PI / 180.0;
+ _params.man_roll_max = math::radians(_params.man_roll_max);
+ _params.man_pitch_max = math::radians(_params.man_pitch_max);
+ _params.man_yaw_max = math::radians(_params.man_yaw_max);
+
+ /* acro control scale */
+ param_get(_params_handles.acro_roll_max, &v);
+ _params.acro_rate_max(0) = math::radians(v);
+ param_get(_params_handles.acro_pitch_max, &v);
+ _params.acro_rate_max(1) = math::radians(v);
+ param_get(_params_handles.acro_yaw_max, &v);
+ _params.acro_rate_max(2) = math::radians(v);
return OK;
}
@@ -478,7 +503,7 @@ MulticopterAttitudeControl::control_attitude(float dt)
if (!_v_control_mode.flag_control_climb_rate_enabled) {
/* pass throttle directly if not in altitude stabilized mode */
- _v_att_sp.thrust = _manual_control_sp.throttle;
+ _v_att_sp.thrust = _manual_control_sp.z;
publish_att_sp = true;
}
@@ -496,8 +521,16 @@ MulticopterAttitudeControl::control_attitude(float dt)
//}
} else {
/* move yaw setpoint */
- yaw_sp_move_rate = _manual_control_sp.yaw * _params.man_yaw_max;
+ yaw_sp_move_rate = _manual_control_sp.r * _params.man_yaw_max;
_v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + yaw_sp_move_rate * dt);
+ float yaw_offs_max = _params.man_yaw_max / _params.att_p(2);
+ float yaw_offs = _wrap_pi(_v_att_sp.yaw_body - _v_att.yaw);
+ if (yaw_offs < - yaw_offs_max) {
+ _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw - yaw_offs_max);
+
+ } else if (yaw_offs > yaw_offs_max) {
+ _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw + yaw_offs_max);
+ }
_v_att_sp.R_valid = false;
publish_att_sp = true;
}
@@ -512,8 +545,8 @@ MulticopterAttitudeControl::control_attitude(float dt)
if (!_v_control_mode.flag_control_velocity_enabled) {
/* update attitude setpoint if not in position control mode */
- _v_att_sp.roll_body = _manual_control_sp.roll * _params.man_roll_max;
- _v_att_sp.pitch_body = -_manual_control_sp.pitch * _params.man_pitch_max;
+ _v_att_sp.roll_body = _manual_control_sp.y * _params.man_roll_max;
+ _v_att_sp.pitch_body = -_manual_control_sp.x * _params.man_pitch_max;
_v_att_sp.R_valid = false;
publish_att_sp = true;
}
@@ -626,6 +659,9 @@ MulticopterAttitudeControl::control_attitude(float dt)
/* calculate angular rates setpoint */
_rates_sp = _params.att_p.emult(e_R);
+ /* limit yaw rate */
+ _rates_sp(2) = math::constrain(_rates_sp(2), -_params.yaw_rate_max, _params.yaw_rate_max);
+
/* feed forward yaw setpoint rate */
_rates_sp(2) += yaw_sp_move_rate * yaw_w * _params.yaw_ff;
}
@@ -762,11 +798,36 @@ MulticopterAttitudeControl::task_main()
} else {
/* attitude controller disabled, poll rates setpoint topic */
- vehicle_rates_setpoint_poll();
- _rates_sp(0) = _v_rates_sp.roll;
- _rates_sp(1) = _v_rates_sp.pitch;
- _rates_sp(2) = _v_rates_sp.yaw;
- _thrust_sp = _v_rates_sp.thrust;
+ if (_v_control_mode.flag_control_manual_enabled) {
+ /* manual rates control - ACRO mode */
+ _rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, _manual_control_sp.r).emult(_params.acro_rate_max);
+ _thrust_sp = _manual_control_sp.z;
+
+ /* reset yaw setpoint after ACRO */
+ _reset_yaw_sp = true;
+
+ /* publish attitude rates setpoint */
+ _v_rates_sp.roll = _rates_sp(0);
+ _v_rates_sp.pitch = _rates_sp(1);
+ _v_rates_sp.yaw = _rates_sp(2);
+ _v_rates_sp.thrust = _thrust_sp;
+ _v_rates_sp.timestamp = hrt_absolute_time();
+
+ if (_v_rates_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp);
+
+ } else {
+ _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp);
+ }
+
+ } else {
+ /* attitude controller disabled, poll rates setpoint topic */
+ vehicle_rates_setpoint_poll();
+ _rates_sp(0) = _v_rates_sp.roll;
+ _rates_sp(1) = _v_rates_sp.pitch;
+ _rates_sp(2) = _v_rates_sp.yaw;
+ _thrust_sp = _v_rates_sp.thrust;
+ }
}
if (_v_control_mode.flag_control_rates_enabled) {
@@ -806,7 +867,7 @@ MulticopterAttitudeControl::start()
_control_task = task_spawn_cmd("mc_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&MulticopterAttitudeControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c
index e52c39368..819847b40 100644
--- a/src/modules/mc_att_control/mc_att_control_params.c
+++ b/src/modules/mc_att_control/mc_att_control_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file mc_att_control_params.c
* Parameters for multicopter attitude controller.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <systemlib/param/param.h>
@@ -175,6 +176,18 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f);
/**
+ * Max yaw rate
+ *
+ * Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 120.0f);
+
+/**
* Max manual roll
*
* @unit deg
@@ -202,3 +215,32 @@ PARAM_DEFINE_FLOAT(MC_MAN_P_MAX, 35.0f);
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MC_MAN_Y_MAX, 120.0f);
+
+/**
+ * Max acro roll rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 90.0f);
+
+/**
+ * Max acro pitch rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 90.0f);
+
+/**
+ * Max acro yaw rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 120.0f);
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 7c625a0c5..09960d106 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -226,7 +226,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace pos_control
@@ -617,7 +617,7 @@ MulticopterPositionControl::task_main()
reset_alt_sp();
/* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
+ sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
}
if (_control_mode.flag_control_position_enabled) {
@@ -625,8 +625,8 @@ MulticopterPositionControl::task_main()
reset_pos_sp();
/* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _manual.pitch;
- sp_move_rate(1) = _manual.roll;
+ sp_move_rate(0) = _manual.x;
+ sp_move_rate(1) = _manual.y;
}
/* limit setpoint move rate */
@@ -782,7 +782,7 @@ MulticopterPositionControl::task_main()
float i = _params.thr_min;
if (reset_int_z_manual) {
- i = _manual.throttle;
+ i = _manual.z;
if (i < _params.thr_min) {
i = _params.thr_min;
@@ -1062,7 +1062,7 @@ MulticopterPositionControl::start()
_control_task = task_spawn_cmd("mc_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&MulticopterPositionControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
index 104df4e59..05ab5769b 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -35,6 +35,8 @@
/**
* @file mc_pos_control_params.c
* Multicopter position controller parameters.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <systemlib/param/param.h>
@@ -98,7 +100,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
/**
* Maximum vertical velocity
*
- * Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY).
+ * Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).
*
* @unit m/s
* @min 0.0
@@ -109,7 +111,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
/**
* Vertical velocity feed forward
*
- * Feed forward weight for altitude control in stabilized modes (SEATBELT, EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ * Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
@@ -154,7 +156,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
/**
* Maximum horizontal velocity
*
- * Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY).
+ * Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).
*
* @unit m/s
* @min 0.0
@@ -165,7 +167,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
/**
* Horizontal velocity feed forward
*
- * Feed forward weight for position control in position control mode (EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ * Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
@@ -176,7 +178,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
/**
* Maximum tilt angle in air
*
- * Limits maximum tilt in AUTO and EASY modes during flight.
+ * Limits maximum tilt in AUTO and POSCTRL modes during flight.
*
* @unit deg
* @min 0.0
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index f452a85f7..bc8dbca50 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file geofence.cpp
* Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "geofence.h"
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
index 9628b7271..2eb126ab5 100644
--- a/src/modules/navigator/geofence.h
+++ b/src/modules/navigator/geofence.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file geofence.h
* Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#ifndef GEOFENCE_H_
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index e95bcfd43..adbb0cfa2 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -139,7 +139,7 @@ Mission::get_current_mission_item(struct mission_item_s *new_mission_item, bool
return true;
}
}
-
+
/* otherwise fallback to offboard */
if (_current_offboard_mission_index < _offboard_mission_item_count) {
@@ -246,7 +246,7 @@ void
Mission::move_to_next()
{
report_mission_item_reached();
-
+
switch (_current_mission_type) {
case MISSION_TYPE_ONBOARD:
_current_onboard_mission_index++;
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
index 0fa2ff3fa..5e0e9702d 100644
--- a/src/modules/navigator/mission.h
+++ b/src/modules/navigator/mission.h
@@ -34,6 +34,8 @@
* @file navigator_mission.h
* Helper class to access missions
* @author Julian Oes <julian@oes.ch>
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef NAVIGATOR_MISSION_H
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
index eaafa217d..2f45f2267 100644
--- a/src/modules/navigator/mission_feasibility_checker.cpp
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file mission_feasibility_checker.cpp
* Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include "mission_feasibility_checker.h"
@@ -100,8 +101,8 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
/* Check if all mission items are inside the geofence (if we have a valid geofence) */
if (geofence.valid()) {
for (size_t i = 0; i < nMissionItems; i++) {
- static struct mission_item_s missionitem;
- const ssize_t len = sizeof(struct mission_item_s);
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
@@ -125,8 +126,8 @@ bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size
for (size_t i = 0; i < nMissionItems; i++) {
- static struct mission_item_s missionitem;
- const ssize_t len = sizeof(struct mission_item_s);
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
return false;
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
index 7a0b2a296..f98e28462 100644
--- a/src/modules/navigator/mission_feasibility_checker.h
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +33,11 @@
/**
* @file mission_feasibility_checker.h
* Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
+
#ifndef MISSION_FEASIBILITY_CHECKER_H_
#define MISSION_FEASIBILITY_CHECKER_H_
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 5f113f686..8913d4d1c 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -47,3 +47,5 @@ SRCS = navigator_main.cpp \
geofence_params.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index d45446e5f..74694447a 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 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
@@ -410,7 +410,7 @@ Navigator::parameters_update()
param_get(_parameter_handles.acceptance_radius, &(_parameters.acceptance_radius));
param_get(_parameter_handles.loiter_radius, &(_parameters.loiter_radius));
param_get(_parameter_handles.onboard_mission_enabled, &(_parameters.onboard_mission_enabled));
- param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
+ param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
_mission.set_onboard_mission_allowed((bool)_parameters.onboard_mission_enabled);
@@ -728,7 +728,7 @@ Navigator::start()
_navigator_task = task_spawn_cmd("navigator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&Navigator::task_main_trampoline,
nullptr);
@@ -946,7 +946,7 @@ Navigator::start_loiter()
mavlink_log_info(_mavlink_fd, "#audio: loiter at current altitude");
_update_triplet = true;
- return true;
+ return true;
}
bool
@@ -999,7 +999,7 @@ Navigator::set_mission_items()
/* convert the current mission item and set it valid */
mission_item_to_position_setpoint(&_mission_item, &_pos_sp_triplet.current);
_pos_sp_triplet.current.valid = true;
-
+
mission_item_s next_mission_item;
@@ -1206,7 +1206,7 @@ Navigator::check_mission_item_reached()
}
if (_waypoint_position_reached && !_waypoint_yaw_reached) {
-
+
/* TODO: removed takeoff, why? */
if (_vstatus.is_rotary_wing && isfinite(_mission_item.yaw)) {
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 49969a382..ad079a250 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
index 939d76849..0658d3f09 100644
--- a/src/modules/position_estimator_inav/module.mk
+++ b/src/modules/position_estimator_inav/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = position_estimator_inav
SRCS = position_estimator_inav_main.c \
position_estimator_inav_params.c \
inertial_filter.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 54c8a7d17..4260623a3 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -135,7 +135,7 @@ int position_estimator_inav_main(int argc, char *argv[])
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
- SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4000,
position_estimator_inav_thread_main,
(argv) ? (const char **) &argv[2] : (const char **) NULL);
exit(0);
@@ -199,6 +199,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float y_est[3] = { 0.0f, 0.0f, 0.0f };
float z_est[3] = { 0.0f, 0.0f, 0.0f };
+ float eph = 1.0;
+ float epv = 1.0;
+
float x_est_prev[3], y_est_prev[3], z_est_prev[3];
memset(x_est_prev, 0, sizeof(x_est_prev));
memset(y_est_prev, 0, sizeof(y_est_prev));
@@ -535,6 +538,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
flow_valid = true;
+ eph = fminf(eph, 0.1 / att.R[2][2] / flow_q * fmaxf(1.0f, flow_dist)); // under ideal conditions, on 1m distance assume EPH = 10cm
+
} else {
w_flow = 0.0f;
flow_valid = false;
@@ -673,6 +678,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_gps[2][1] = 0.0f;
}
+ eph = fminf(eph, gps.eph);
+ epv = fminf(epv, gps.epv);
+
w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph);
w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv);
}
@@ -712,6 +720,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
dt = fmaxf(fminf(0.02, dt), 0.002); // constrain dt from 2 to 20 ms
t_prev = t;
+ /* increase EPH/EPV on each step */
+ eph *= 1.0 + dt;
+ epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
+
/* use GPS if it's valid and reference position initialized */
bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
@@ -723,7 +735,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
xy_src_time = t;
}
- bool can_estimate_xy = (t < xy_src_time + xy_src_timeout);
+ bool can_estimate_xy = eph < max_eph_epv * 1.5;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
@@ -922,6 +934,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.landed = landed;
local_pos.yaw = att.yaw;
local_pos.dist_bottom_valid = dist_bottom_valid;
+ local_pos.eph = eph;
+ local_pos.epv = epv;
if (local_pos.dist_bottom_valid) {
local_pos.dist_bottom = -z_est[0] - surface_offset;
@@ -950,9 +964,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.yaw = local_pos.yaw;
- // TODO implement dead-reckoning
- global_pos.eph = gps.eph;
- global_pos.epv = gps.epv;
+ global_pos.eph = eph;
+ global_pos.epv = epv;
if (vehicle_global_position_pub < 0) {
vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 56c5aa005..62e6b12cb 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -291,6 +291,7 @@ controls_tick() {
/* set RC OK flag, as we got an update */
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_OK;
/* if we have enough channels (5) to control the vehicle, the mapping is ok */
if (assigned_channels > 4) {
@@ -336,6 +337,9 @@ controls_tick() {
PX4IO_P_STATUS_FLAGS_OVERRIDE |
PX4IO_P_STATUS_FLAGS_RC_OK);
+ /* flag raw RC as lost */
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_RC_OK);
+
/* Mark all channels as invalid, as we just lost the RX */
r_rc_valid = 0;
@@ -405,8 +409,9 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
if (*num_values > PX4IO_RC_INPUT_CHANNELS)
*num_values = PX4IO_RC_INPUT_CHANNELS;
- for (unsigned i = 0; i < *num_values; i++)
+ for (unsigned i = 0; i < *num_values; i++) {
values[i] = ppm_buffer[i];
+ }
/* clear validity */
ppm_last_valid_decode = 0;
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index ebf4f3e8e..2f721bf1e 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -213,6 +213,7 @@ mixer_tick(void)
mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
in_mixer = false;
+ /* the pwm limit call takes care of out of band errors */
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 6c20d6006..7471faec7 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -142,6 +142,7 @@
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */
+#define PX4IO_P_RAW_RC_FLAGS_RC_OK (1 << 4) /* RC reception ok */
#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
@@ -189,6 +190,8 @@
#define PX4IO_P_SETUP_RELAYS_POWER2 (1<<1) /* hardware rev [1] power relay 2 */
#define PX4IO_P_SETUP_RELAYS_ACC1 (1<<2) /* hardware rev [1] accessory power 1 */
#define PX4IO_P_SETUP_RELAYS_ACC2 (1<<3) /* hardware rev [1] accessory power 2 */
+#else
+#define PX4IO_P_SETUP_RELAYS_PAD 5
#endif
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
@@ -208,15 +211,16 @@ enum { /* DSM bind states */
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
- /* 12 occupied by CRC */
+ /* storage space of 12 occupied by CRC */
+#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
+ 'armed' (PWM enabled) state - this is a non-data write and
+ hence index 12 can safely be used. */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
-#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
- 'armed' (PWM enabled) state */
-#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
+#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
/* autopilot control values, -10000..10000 */
-#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
+#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index fd7c6081f..db1836f4a 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -160,6 +160,9 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_PWM_ALTRATE] = 200,
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
[PX4IO_P_SETUP_RELAYS] = 0,
+#else
+ /* this is unused, but we will pad it for readability (the compiler pads it automatically) */
+ [PX4IO_P_SETUP_RELAYS_PAD] = 0,
#endif
#ifdef ADC_VSERVO
[PX4IO_P_SETUP_VSERVO_SCALE] = 10000,
@@ -523,18 +526,22 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_PWM_DEFAULTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, value, r_setup_pwm_altrate);
break;
case PX4IO_P_SETUP_PWM_ALTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, r_setup_pwm_defaultrate, value);
break;
@@ -566,8 +573,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
// check the magic value
- if (value != PX4IO_REBOOT_BL_MAGIC)
+ if (value != PX4IO_REBOOT_BL_MAGIC) {
break;
+ }
// we schedule a reboot rather than rebooting
// immediately to allow the IO board to ACK
@@ -585,6 +593,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
break;
+ case PX4IO_P_SETUP_RC_THR_FAILSAFE_US:
+ if (value > 650 && value < 2350) {
+ r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US] = value;
+ }
+ break;
+
default:
return -1;
}
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
index f53129688..a28d43e72 100644
--- a/src/modules/sdlog2/module.mk
+++ b/src/modules/sdlog2/module.mk
@@ -41,3 +41,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
SRCS = sdlog2.c \
logbuffer.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 5d49cc4c9..66a9e31c6 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -89,6 +89,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
#include <version/version.h>
#include <mavlink/mavlink_log.h>
@@ -97,6 +98,36 @@
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
+/**
+ * Logging rate.
+ *
+ * A value of -1 indicates the commandline argument
+ * should be obeyed. A value of 0 sets the minimum rate,
+ * any other value is interpreted as rate in Hertz. This
+ * parameter is only read out before logging starts (which
+ * commonly is before arming).
+ *
+ * @min -1
+ * @max 1
+ * @group SD Logging
+ */
+PARAM_DEFINE_INT32(SDLOG_RATE, -1);
+
+/**
+ * Enable extended logging mode.
+ *
+ * A value of -1 indicates the commandline argument
+ * should be obeyed. A value of 0 disables extended
+ * logging mode, a value of 1 enables it. This
+ * parameter is only read out before logging starts
+ * (which commonly is before arming).
+ *
+ * @min -1
+ * @max 1
+ * @group SD Logging
+ */
+PARAM_DEFINE_INT32(SDLOG_EXT, -1);
+
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
} else { \
@@ -112,12 +143,14 @@ static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
-static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
-static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
+static const unsigned MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
+static const unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
+static bool _extended_logging = false;
+
static const char *log_root = "/fs/microsd/log";
static int mavlink_fd = -1;
struct logbuffer_s lb;
@@ -218,6 +251,8 @@ static int create_log_dir(void);
*/
static int open_log_file(void);
+static int open_perf_file(const char* str);
+
static void
sdlog2_usage(const char *reason)
{
@@ -225,12 +260,13 @@ sdlog2_usage(const char *reason)
fprintf(stderr, "%s\n", reason);
}
- errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
+ errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t -x\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
"\t-a\tLog only when armed (can be still overriden by command)\n"
- "\t-t\tUse date/time for naming log directories and files\n");
+ "\t-t\tUse date/time for naming log directories and files\n"
+ "\t-x\tExtended logging");
}
/**
@@ -349,8 +385,8 @@ int create_log_dir()
int open_log_file()
{
/* string to hold the path to the log */
- char log_file_name[16] = "";
- char log_file_path[48] = "";
+ char log_file_name[32] = "";
+ char log_file_path[64] = "";
if (log_name_timestamp && gps_time != 0) {
/* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
@@ -378,7 +414,58 @@ int open_log_file()
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
- warnx("all %d possible files exist already", MAX_NO_LOGFILE);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
+ return -1;
+ }
+ }
+
+ int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
+
+ if (fd < 0) {
+ warn("failed opening log: %s", log_file_name);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
+
+ } else {
+ warnx("log file: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name);
+ }
+
+ return fd;
+}
+
+int open_perf_file(const char* str)
+{
+ /* string to hold the path to the log */
+ char log_file_name[32] = "";
+ char log_file_path[64] = "";
+
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ strftime(log_file_name, sizeof(log_file_name), "perf%H_%M_%S.txt", &t);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
+
+ } else {
+ unsigned file_number = 1; // start with file log001
+
+ /* look for the next file that does not exist */
+ while (file_number <= MAX_NO_LOGFILE) {
+ /* format log file path: e.g. /fs/microsd/sess001/log001.bin */
+ snprintf(log_file_name, sizeof(log_file_name), "perf%03u.txt", file_number);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
+
+ if (!file_exist(log_file_path)) {
+ break;
+ }
+
+ file_number++;
+ }
+
+ if (file_number > MAX_NO_LOGFILE) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
+ mavlink_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
return -1;
}
}
@@ -387,7 +474,7 @@ int open_log_file()
if (fd < 0) {
warn("failed opening log: %s", log_file_name);
- mavlink_log_info(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
} else {
warnx("log file: %s", log_file_name);
@@ -529,6 +616,12 @@ void sdlog2_start_log()
errx(1, "error creating logwriter thread");
}
+ /* write all performance counters */
+ int perf_fd = open_perf_file("preflight");
+ dprintf(perf_fd, "PERFORMANCE COUNTERS PRE-FLIGHT\n\n");
+ perf_print_all(perf_fd);
+ close(perf_fd);
+
logging_enabled = true;
}
@@ -556,6 +649,12 @@ void sdlog2_stop_log()
logwriter_pthread = 0;
pthread_attr_destroy(&logwriter_attr);
+ /* write all performance counters */
+ int perf_fd = open_perf_file("postflight");
+ dprintf(perf_fd, "PERFORMANCE COUNTERS POST-FLIGHT\n\n");
+ perf_print_all(perf_fd);
+ close(perf_fd);
+
sdlog2_status();
}
@@ -572,7 +671,7 @@ int write_formats(int fd)
int written = 0;
/* fill message format packet for each format and write it */
- for (int i = 0; i < log_formats_num; i++) {
+ for (unsigned i = 0; i < log_formats_num; i++) {
log_msg_format.body = log_formats[i];
written += write(fd, &log_msg_format, sizeof(log_msg_format));
}
@@ -679,12 +778,12 @@ int sdlog2_thread_main(int argc, char *argv[])
* set error flag instead */
bool err_flag = false;
- while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
+ while ((ch = getopt(argc, argv, "r:b:eatx")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
- if (r <= 0) {
+ if (r == 0) {
r = 1;
}
@@ -715,6 +814,10 @@ int sdlog2_thread_main(int argc, char *argv[])
log_name_timestamp = true;
break;
+ case 'x':
+ _extended_logging = true;
+ break;
+
case '?':
if (optopt == 'c') {
warnx("option -%c requires an argument", optopt);
@@ -741,6 +844,44 @@ int sdlog2_thread_main(int argc, char *argv[])
gps_time = 0;
+ /* interpret logging params */
+
+ param_t log_rate_ph = param_find("SDLOG_RATE");
+
+ if (log_rate_ph != PARAM_INVALID) {
+ int32_t param_log_rate;
+ param_get(log_rate_ph, &param_log_rate);
+
+ if (param_log_rate > 0) {
+
+ /* we can't do more than ~ 500 Hz, even with a massive buffer */
+ if (param_log_rate > 500) {
+ param_log_rate = 500;
+ }
+
+ sleep_delay = 1000000 / param_log_rate;
+ } else if (param_log_rate == 0) {
+ /* we need at minimum 10 Hz to be able to see anything */
+ sleep_delay = 1000000 / 10;
+ }
+ }
+
+ param_t log_ext_ph = param_find("SDLOG_EXT");
+
+ if (log_ext_ph != PARAM_INVALID) {
+
+ int32_t param_log_extended;
+ param_get(log_ext_ph, &param_log_extended);
+
+ if (param_log_extended > 0) {
+ _extended_logging = true;
+ } else if (param_log_extended == 0) {
+ _extended_logging = false;
+ }
+ /* any other value means to ignore the parameter, so no else case */
+
+ }
+
/* create log root dir */
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
@@ -834,6 +975,10 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_ESTM_s log_ESTM;
struct log_PWR_s log_PWR;
struct log_VICN_s log_VICN;
+ struct log_GS0A_s log_GS0A;
+ struct log_GS0B_s log_GS0B;
+ struct log_GS1A_s log_GS1A;
+ struct log_GS1B_s log_GS1B;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -967,8 +1112,17 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(STAT);
}
- /* --- GPS POSITION --- */
+ /* --- GPS POSITION - UNIT #1 --- */
if (gps_pos_updated) {
+
+ float snr_mean = 0.0f;
+
+ for (unsigned i = 0; i < buf_gps_pos.satellites_visible; i++) {
+ snr_mean += buf_gps_pos.satellite_snr[i];
+ }
+
+ snr_mean /= buf_gps_pos.satellites_visible;
+
log_msg.msg_type = LOG_GPS_MSG;
log_msg.body.log_GPS.gps_time = buf_gps_pos.time_gps_usec;
log_msg.body.log_GPS.fix_type = buf_gps_pos.fix_type;
@@ -981,7 +1135,48 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPS.vel_e = buf_gps_pos.vel_e_m_s;
log_msg.body.log_GPS.vel_d = buf_gps_pos.vel_d_m_s;
log_msg.body.log_GPS.cog = buf_gps_pos.cog_rad;
+ log_msg.body.log_GPS.sats = buf_gps_pos.satellites_visible;
+ log_msg.body.log_GPS.snr_mean = snr_mean;
+ log_msg.body.log_GPS.noise_per_ms = buf_gps_pos.noise_per_ms;
+ log_msg.body.log_GPS.jamming_indicator = buf_gps_pos.jamming_indicator;
LOGBUFFER_WRITE_AND_COUNT(GPS);
+
+ if (_extended_logging) {
+ /* log the SNR of each satellite for a detailed view of signal quality */
+ unsigned gps_msg_max_snr = sizeof(buf_gps_pos.satellite_snr) / sizeof(buf_gps_pos.satellite_snr[0]);
+ unsigned log_max_snr = sizeof(log_msg.body.log_GS0A.satellite_snr) / sizeof(log_msg.body.log_GS0A.satellite_snr[0]);
+
+ log_msg.msg_type = LOG_GS0A_MSG;
+ memset(&log_msg.body.log_GS0A, 0, sizeof(log_msg.body.log_GS0A));
+ /* fill set A */
+ for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+
+ int satindex = buf_gps_pos.satellite_prn[i] - 1;
+
+ /* handles index exceeding and wraps to to arithmetic errors */
+ if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
+ /* map satellites by their ID so that logs from two receivers can be compared */
+ log_msg.body.log_GS0A.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ }
+ }
+ LOGBUFFER_WRITE_AND_COUNT(GS0A);
+
+ log_msg.msg_type = LOG_GS0B_MSG;
+ memset(&log_msg.body.log_GS0B, 0, sizeof(log_msg.body.log_GS0B));
+ /* fill set B */
+ for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+
+ /* get second bank of satellites, thus deduct bank size from index */
+ int satindex = buf_gps_pos.satellite_prn[i] - 1 - log_max_snr;
+
+ /* handles index exceeding and wraps to to arithmetic errors */
+ if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
+ /* map satellites by their ID so that logs from two receivers can be compared */
+ log_msg.body.log_GS0B.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ }
+ }
+ LOGBUFFER_WRITE_AND_COUNT(GS0B);
+ }
}
/* --- SENSOR COMBINED --- */
@@ -1105,10 +1300,16 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat * 1e7;
log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon * 1e7;
log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
- log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
- log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.pos_flags = (buf.local_pos.xy_valid ? 1 : 0) |
+ (buf.local_pos.z_valid ? 2 : 0) |
+ (buf.local_pos.v_xy_valid ? 4 : 0) |
+ (buf.local_pos.v_z_valid ? 8 : 0) |
+ (buf.local_pos.xy_global ? 16 : 0) |
+ (buf.local_pos.z_global ? 32 : 0);
log_msg.body.log_LPOS.landed = buf.local_pos.landed;
log_msg.body.log_LPOS.ground_dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
+ log_msg.body.log_LPOS.eph = buf.local_pos.eph;
+ log_msg.body.log_LPOS.epv = buf.local_pos.epv;
LOGBUFFER_WRITE_AND_COUNT(LPOS);
}
@@ -1320,6 +1521,7 @@ void sdlog2_status()
float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ warnx("extended logging: %s", (_extended_logging) ? "ON" : "OFF");
mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 595a787d6..f4d88f079 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -109,10 +109,11 @@ struct log_LPOS_s {
int32_t ref_lat;
int32_t ref_lon;
float ref_alt;
- uint8_t xy_flags;
- uint8_t z_flags;
+ uint8_t pos_flags;
uint8_t landed;
uint8_t ground_dist_flags;
+ float eph;
+ float epv;
};
/* --- LPSP - LOCAL POSITION SETPOINT --- */
@@ -138,6 +139,10 @@ struct log_GPS_s {
float vel_e;
float vel_d;
float cog;
+ uint8_t sats;
+ uint16_t snr_mean;
+ uint16_t noise_per_ms;
+ uint16_t jamming_indicator;
};
/* --- ATTC - ATTITUDE CONTROLS (ACTUATOR_0 CONTROLS)--- */
@@ -317,6 +322,30 @@ struct log_VICN_s {
float yaw;
};
+/* --- GS0A - GPS SNR #0, SAT GROUP A --- */
+#define LOG_GS0A_MSG 26
+struct log_GS0A_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS0B - GPS SNR #0, SAT GROUP B --- */
+#define LOG_GS0B_MSG 27
+struct log_GS0B_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS1A - GPS SNR #1, SAT GROUP A --- */
+#define LOG_GS1A_MSG 28
+struct log_GS1A_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS1B - GPS SNR #1, SAT GROUP B --- */
+#define LOG_GS1B_MSG 29
+struct log_GS1B_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -348,9 +377,9 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
- LOG_FORMAT(LPOS, "ffffffffLLfBBBB", "X,Y,Z,dist,distR,VX,VY,VZ,RLat,RLon,RAlt,XYFlg,ZFlg,LFlg,GFlg"),
+ LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
- LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
+ LOG_FORMAT(GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT(STAT, "BBBfBB", "MainState,ArmState,FailsafeState,BatRem,BatWarn,Landed"),
LOG_FORMAT(RC, "ffffffffBB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost"),
@@ -368,6 +397,10 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,nStat,statNaN,covNaN,kGainNaN"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
+ LOG_FORMAT(GS0A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
index 96a443c6e..91230a37c 100644
--- a/src/modules/segway/BlockSegwayController.cpp
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -35,8 +35,8 @@ void BlockSegwayController::update() {
// handle autopilot modes
if (_status.main_state == MAIN_STATE_AUTO ||
- _status.main_state == MAIN_STATE_SEATBELT ||
- _status.main_state == MAIN_STATE_EASY) {
+ _status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index aa538fd6b..5b1bc5e86 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
SRCS = sensors.cpp \
sensor_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index bc49f5c85..999cf8bb3 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -488,6 +488,15 @@ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
+#elif CONFIG_ARCH_BOARD_AEROCORE
+/**
+ * Scaling factor for battery voltage sensor on AeroCore.
+ *
+ * For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063
+ *
+ * @group Battery Calibration
+ */
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0063f);
#else
/**
* Scaling factor for battery voltage sensor on FMU v1.
@@ -536,6 +545,20 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
/**
+ * Failsafe channel mapping.
+ *
+ * The RC mapping index indicates which channel is used for failsafe
+ * If 0, whichever channel is mapped to throttle is used
+ * otherwise the value indicates the specific rc channel to use
+ *
+ * @min 0
+ * @max 18
+ *
+ *
+ */
+PARAM_DEFINE_INT32(RC_MAP_FAILSAFE, 0); //Default to throttle function
+
+/**
* Throttle control channel mapping.
*
* The channel index (starting from 1 for channel 1) indicates
@@ -585,13 +608,13 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
/**
- * Assist switch channel mapping.
+ * Posctl switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0);
/**
* Loiter switch channel mapping.
@@ -602,7 +625,14 @@ PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
*/
PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
-//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+/**
+ * Acro switch channel mapping.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
/**
* Flaps channel mapping.
@@ -655,3 +685,99 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_FAILS_THR, 0);
+
+/**
+ * Threshold for selecting assist mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_ASSIST_TH, 0.25f);
+
+/**
+ * Threshold for selecting auto mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
+
+/**
+ * Threshold for selecting posctl mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_POSCTL_TH, 0.5f);
+
+/**
+ * Threshold for selecting return to launch mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f);
+
+/**
+ * Threshold for selecting loiter mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
+
+/**
+ * Threshold for selecting acro mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index e260aae45..b268b1b36 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -126,6 +126,12 @@
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+#define ADC_BATTERY_VOLTAGE_CHANNEL 10
+#define ADC_BATTERY_CURRENT_CHANNEL -1
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL -1
+#endif
+
#define BATT_V_LOWPASS 0.001f
#define BATT_V_IGNORE_THRESHOLD 3.5f
@@ -175,7 +181,8 @@ private:
/**
* Get switch position for specified function.
*/
- switch_pos_t get_rc_switch_position(enum RC_CHANNELS_FUNCTION func);
+ switch_pos_t get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv);
+ switch_pos_t get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv);
/**
* Gather and publish RC input data.
@@ -219,8 +226,8 @@ private:
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
- math::Matrix<3,3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
- math::Matrix<3,3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
+ math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
+ math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
uint64_t _battery_discharged; /**< battery discharged current in mA*ms */
@@ -250,13 +257,13 @@ private:
int rc_map_pitch;
int rc_map_yaw;
int rc_map_throttle;
+ int rc_map_failsafe;
int rc_map_mode_sw;
int rc_map_return_sw;
- int rc_map_assisted_sw;
+ int rc_map_posctl_sw;
int rc_map_loiter_sw;
-
-// int rc_map_offboard_ctrl_mode_sw;
+ int rc_map_acro_sw;
int rc_map_flaps;
@@ -266,7 +273,19 @@ private:
int rc_map_aux4;
int rc_map_aux5;
- int32_t rc_fs_thr;
+ int32_t rc_fails_thr;
+ float rc_assist_th;
+ float rc_auto_th;
+ float rc_posctl_th;
+ float rc_return_th;
+ float rc_loiter_th;
+ float rc_acro_th;
+ bool rc_assist_inv;
+ bool rc_auto_inv;
+ bool rc_posctl_inv;
+ bool rc_return_inv;
+ bool rc_loiter_inv;
+ bool rc_acro_inv;
float battery_voltage_scaling;
float battery_current_scaling;
@@ -293,13 +312,13 @@ private:
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
+ param_t rc_map_failsafe;
param_t rc_map_mode_sw;
param_t rc_map_return_sw;
- param_t rc_map_assisted_sw;
+ param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
-
-// param_t rc_map_offboard_ctrl_mode_sw;
+ param_t rc_map_acro_sw;
param_t rc_map_flaps;
@@ -309,7 +328,13 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
- param_t rc_fs_thr;
+ param_t rc_fails_thr;
+ param_t rc_assist_th;
+ param_t rc_auto_th;
+ param_t rc_posctl_th;
+ param_t rc_return_th;
+ param_t rc_loiter_th;
+ param_t rc_acro_th;
param_t battery_voltage_scaling;
param_t battery_current_scaling;
@@ -416,7 +441,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace sensors
@@ -499,6 +524,7 @@ Sensors::Sensors() :
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
_parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW");
_parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
+ _parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
_parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
@@ -507,10 +533,9 @@ Sensors::Sensors() :
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
- _parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
+ _parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
-
-// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
+ _parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -518,8 +543,14 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
- /* RC failsafe */
- _parameter_handles.rc_fs_thr = param_find("RC_FAILS_THR");
+ /* RC thresholds */
+ _parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
+ _parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
+ _parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
+ _parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
+ _parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
+ _parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
+ _parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
@@ -620,8 +651,9 @@ Sensors::parameters_update()
}
/* handle wrong values */
- if (!rc_valid)
+ if (!rc_valid) {
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
+ }
const char *paramerr = "FAIL PARM LOAD";
@@ -642,6 +674,10 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
+ if (param_get(_parameter_handles.rc_map_failsafe, &(_parameters.rc_map_failsafe)) != OK) {
+ warnx("%s", paramerr);
+ }
+
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
warnx("%s", paramerr);
}
@@ -650,7 +686,7 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
+ if (param_get(_parameter_handles.rc_map_posctl_sw, &(_parameters.rc_map_posctl_sw)) != OK) {
warnx("%s", paramerr);
}
@@ -658,20 +694,38 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ if (param_get(_parameter_handles.rc_map_acro_sw, &(_parameters.rc_map_acro_sw)) != OK) {
warnx("%s", paramerr);
}
-// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
-// warnx("Failed getting offboard control mode sw chan index");
-// }
+ if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ warnx("%s", paramerr);
+ }
param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2));
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
- param_get(_parameter_handles.rc_fs_thr, &(_parameters.rc_fs_thr));
+ param_get(_parameter_handles.rc_fails_thr, &(_parameters.rc_fails_thr));
+ param_get(_parameter_handles.rc_assist_th, &(_parameters.rc_assist_th));
+ _parameters.rc_assist_inv = (_parameters.rc_assist_th < 0);
+ _parameters.rc_assist_th = fabs(_parameters.rc_assist_th);
+ param_get(_parameter_handles.rc_auto_th, &(_parameters.rc_auto_th));
+ _parameters.rc_auto_inv = (_parameters.rc_auto_th < 0);
+ _parameters.rc_auto_th = fabs(_parameters.rc_auto_th);
+ param_get(_parameter_handles.rc_posctl_th, &(_parameters.rc_posctl_th));
+ _parameters.rc_posctl_inv = (_parameters.rc_posctl_th < 0);
+ _parameters.rc_posctl_th = fabs(_parameters.rc_posctl_th);
+ param_get(_parameter_handles.rc_return_th, &(_parameters.rc_return_th));
+ _parameters.rc_return_inv = (_parameters.rc_return_th < 0);
+ _parameters.rc_return_th = fabs(_parameters.rc_return_th);
+ param_get(_parameter_handles.rc_loiter_th, &(_parameters.rc_loiter_th));
+ _parameters.rc_loiter_inv = (_parameters.rc_loiter_th < 0);
+ _parameters.rc_loiter_th = fabs(_parameters.rc_loiter_th);
+ param_get(_parameter_handles.rc_acro_th, &(_parameters.rc_acro_th));
+ _parameters.rc_acro_inv = (_parameters.rc_acro_th < 0);
+ _parameters.rc_acro_th = fabs(_parameters.rc_acro_th);
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -681,13 +735,12 @@ Sensors::parameters_update()
_rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
- _rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
+ _rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
+ _rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
-// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
-
_rc.function[AUX_1] = _parameters.rc_map_aux1 - 1;
_rc.function[AUX_2] = _parameters.rc_map_aux2 - 1;
_rc.function[AUX_3] = _parameters.rc_map_aux3 - 1;
@@ -765,7 +818,7 @@ Sensors::accel_init()
/* set the driver to poll at 1000Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
-#elif CONFIG_ARCH_BOARD_PX4FMU_V2
+#elif CONFIG_ARCH_BOARD_PX4FMU_V2 || CONFIG_ARCH_BOARD_AEROCORE
/* set the accel internal sampling rate up to at leat 800Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
@@ -774,7 +827,7 @@ Sensors::accel_init()
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#else
-#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1, CONFIG_ARCH_BOARD_PX4FMU_V2 or CONFIG_ARCH_BOARD_AEROCORE
#endif
@@ -800,12 +853,14 @@ Sensors::gyro_init()
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the gyro internal sampling rate up to at least 1000Hz */
- if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
+ if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK) {
ioctl(fd, GYROIOCSSAMPLERATE, 800);
+ }
/* set the driver to poll at 1000Hz */
- if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK) {
ioctl(fd, SENSORIOCSPOLLRATE, 800);
+ }
#else
@@ -860,12 +915,15 @@ Sensors::mag_init()
ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
- if (ret < 0)
+ if (ret < 0) {
errx(1, "FATAL: unknown if magnetometer is external or onboard");
- else if (ret == 1)
+
+ } else if (ret == 1) {
_mag_is_external = true;
- else
+
+ } else {
_mag_is_external = false;
+ }
close(fd);
}
@@ -965,10 +1023,12 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z);
- if (_mag_is_external)
+ if (_mag_is_external) {
vect = _external_mag_rotation * vect;
- else
+
+ } else {
vect = _board_rotation * vect;
+ }
raw.magnetometer_ga[0] = vect(0);
raw.magnetometer_ga[1] = vect(1);
@@ -1086,8 +1146,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.gyro_scale[2],
};
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale)) {
warn("WARNING: failed to set scale / offsets for gyro");
+ }
close(fd);
@@ -1101,8 +1162,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.accel_scale[2],
};
- if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale))
+ if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) {
warn("WARNING: failed to set scale / offsets for accel");
+ }
close(fd);
@@ -1116,8 +1178,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.mag_scale[2],
};
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale)) {
warn("WARNING: failed to set scale / offsets for mag");
+ }
close(fd);
@@ -1131,8 +1194,10 @@ Sensors::parameter_update_poll(bool forced)
1.0f,
};
- if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ }
+
close(fd);
}
@@ -1150,10 +1215,12 @@ void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
/* only read if publishing */
- if (!_publishing)
+ if (!_publishing) {
return;
+ }
hrt_abstime t = hrt_absolute_time();
+
/* rate limit to 100 Hz */
if (t - _last_adc >= 10000) {
/* make space for a maximum of twelve channels (to ensure reading all channels at once) */
@@ -1178,6 +1245,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
if (voltage > BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_v = voltage;
+
/* one-time initialization of low-pass value to avoid long init delays */
if (_battery_status.voltage_filtered_v < BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_filtered_v = voltage;
@@ -1196,19 +1264,24 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
/* handle current only if voltage is valid */
if (_battery_status.voltage_v > 0.0f) {
float current = (buf_adc[i].am_data * _parameters.battery_current_scaling);
+
/* check measured current value */
if (current >= 0.0f) {
_battery_status.timestamp = t;
_battery_status.current_a = current;
+
if (_battery_current_timestamp != 0) {
/* initialize discharged value */
- if (_battery_status.discharged_mah < 0.0f)
+ if (_battery_status.discharged_mah < 0.0f) {
_battery_status.discharged_mah = 0.0f;
+ }
+
_battery_discharged += current * (t - _battery_current_timestamp);
_battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
}
}
}
+
_battery_current_timestamp = t;
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
@@ -1241,7 +1314,9 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
}
+
_last_adc = t;
+
if (_battery_status.voltage_filtered_v > BATT_V_IGNORE_THRESHOLD) {
/* announce the battery status if needed, just publish else */
if (_battery_pub > 0) {
@@ -1260,6 +1335,7 @@ Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max
{
if (_rc.function[func] >= 0) {
float value = _rc.chan[_rc.function[func]].scaled;
+
if (value < min_value) {
return min_value;
@@ -1269,24 +1345,44 @@ Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max
} else {
return value;
}
+
} else {
return 0.0f;
}
}
switch_pos_t
-Sensors::get_rc_switch_position(enum RC_CHANNELS_FUNCTION func)
+Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv)
{
if (_rc.function[func] >= 0) {
- float value = _rc.chan[_rc.function[func]].scaled;
- if (value > STICK_ON_OFF_LIMIT) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
- } else if (value < -STICK_ON_OFF_LIMIT) {
+ } else if (mid_inv ? value < mid_th : value > mid_th) {
+ return SWITCH_POS_MIDDLE;
+
+ } else {
return SWITCH_POS_OFF;
+ }
+
+ } else {
+ return SWITCH_POS_NONE;
+ }
+}
+
+switch_pos_t
+Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
+{
+ if (_rc.function[func] >= 0) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
+ return SWITCH_POS_ON;
} else {
- return SWITCH_POS_MIDDLE;
+ return SWITCH_POS_OFF;
}
} else {
@@ -1318,13 +1414,18 @@ Sensors::rc_poll()
/* signal looks good */
signal_lost = false;
- /* check throttle failsafe */
- int8_t thr_ch = _rc.function[THROTTLE];
- if (_parameters.rc_fs_thr > 0 && thr_ch >= 0) {
- /* throttle failsafe configured */
- if ((_parameters.rc_fs_thr < _parameters.min[thr_ch] && rc_input.values[thr_ch] < _parameters.rc_fs_thr) ||
- (_parameters.rc_fs_thr > _parameters.max[thr_ch] && rc_input.values[thr_ch] > _parameters.rc_fs_thr)) {
- /* throttle failsafe triggered, signal is lost by receiver */
+ /* check failsafe */
+ int8_t fs_ch = _rc.function[_parameters.rc_map_failsafe]; // get channel mapped to throttle
+
+ if (_parameters.rc_map_failsafe > 0) { // if not 0, use channel number instead of rc.function mapping
+ fs_ch = _parameters.rc_map_failsafe - 1;
+ }
+
+ if (_parameters.rc_fails_thr > 0 && fs_ch >= 0) {
+ /* failsafe configured */
+ if ((_parameters.rc_fails_thr < _parameters.min[fs_ch] && rc_input.values[fs_ch] < _parameters.rc_fails_thr) ||
+ (_parameters.rc_fails_thr > _parameters.max[fs_ch] && rc_input.values[fs_ch] > _parameters.rc_fails_thr)) {
+ /* failsafe triggered, signal is lost by receiver */
signal_lost = true;
}
}
@@ -1332,8 +1433,9 @@ Sensors::rc_poll()
unsigned channel_limit = rc_input.channel_count;
- if (channel_limit > _rc_max_chan_count)
+ if (channel_limit > _rc_max_chan_count) {
channel_limit = _rc_max_chan_count;
+ }
/* read out and scale values from raw message even if signal is invalid */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1341,11 +1443,13 @@ Sensors::rc_poll()
/*
* 1) Constrain to min/max values, as later processing depends on bounds.
*/
- if (rc_input.values[i] < _parameters.min[i])
+ if (rc_input.values[i] < _parameters.min[i]) {
rc_input.values[i] = _parameters.min[i];
+ }
- if (rc_input.values[i] > _parameters.max[i])
+ if (rc_input.values[i] > _parameters.max[i]) {
rc_input.values[i] = _parameters.max[i];
+ }
/*
* 2) Scale around the mid point differently for lower and upper range.
@@ -1377,8 +1481,9 @@ Sensors::rc_poll()
_rc.chan[i].scaled *= _parameters.rev[i];
/* handle any parameter-induced blowups */
- if (!isfinite(_rc.chan[i].scaled))
+ if (!isfinite(_rc.chan[i].scaled)) {
_rc.chan[i].scaled = 0.0f;
+ }
}
_rc.chan_count = rc_input.channel_count;
@@ -1402,10 +1507,10 @@ Sensors::rc_poll()
manual.timestamp = rc_input.timestamp_last_signal;
/* limit controls */
- manual.roll = get_rc_value(ROLL, -1.0, 1.0);
- manual.pitch = get_rc_value(PITCH, -1.0, 1.0);
- manual.yaw = get_rc_value(YAW, -1.0, 1.0);
- manual.throttle = get_rc_value(THROTTLE, 0.0, 1.0);
+ manual.y = get_rc_value(ROLL, -1.0, 1.0);
+ manual.x = get_rc_value(PITCH, -1.0, 1.0);
+ manual.r = get_rc_value(YAW, -1.0, 1.0);
+ manual.z = get_rc_value(THROTTLE, 0.0, 1.0);
manual.flaps = get_rc_value(FLAPS, -1.0, 1.0);
manual.aux1 = get_rc_value(AUX_1, -1.0, 1.0);
manual.aux2 = get_rc_value(AUX_2, -1.0, 1.0);
@@ -1414,10 +1519,11 @@ Sensors::rc_poll()
manual.aux5 = get_rc_value(AUX_5, -1.0, 1.0);
/* mode switches */
- manual.mode_switch = get_rc_switch_position(MODE);
- manual.assisted_switch = get_rc_switch_position(ASSISTED);
- manual.loiter_switch = get_rc_switch_position(LOITER);
- manual.return_switch = get_rc_switch_position(RETURN);
+ manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assist_th, _parameters.rc_assist_inv);
+ manual.posctl_switch = get_rc_sw2pos_position(POSCTL, _parameters.rc_posctl_th, _parameters.rc_posctl_inv);
+ manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
+ manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
+ manual.acro_switch = get_rc_sw2pos_position(ACRO, _parameters.rc_acro_th, _parameters.rc_acro_inv);
/* publish manual_control_setpoint topic */
if (_manual_control_pub > 0) {
@@ -1433,10 +1539,10 @@ Sensors::rc_poll()
actuator_group_3.timestamp = rc_input.timestamp_last_signal;
- actuator_group_3.control[0] = manual.roll;
- actuator_group_3.control[1] = manual.pitch;
- actuator_group_3.control[2] = manual.yaw;
- actuator_group_3.control[3] = manual.throttle;
+ actuator_group_3.control[0] = manual.y;
+ actuator_group_3.control[1] = manual.x;
+ actuator_group_3.control[2] = manual.r;
+ actuator_group_3.control[3] = manual.z;
actuator_group_3.control[4] = manual.flaps;
actuator_group_3.control[5] = manual.aux1;
actuator_group_3.control[6] = manual.aux2;
@@ -1560,8 +1666,9 @@ Sensors::task_main()
diff_pres_poll(raw);
/* Inform other processes that new data is available to copy */
- if (_publishing)
+ if (_publishing) {
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
+ }
/* Look for new r/c input data */
rc_poll();
@@ -1584,7 +1691,7 @@ Sensors::start()
_sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&Sensors::task_main_trampoline,
nullptr);
@@ -1598,18 +1705,21 @@ Sensors::start()
int sensors_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
errx(1, "usage: sensors {start|stop|status}");
+ }
if (!strcmp(argv[1], "start")) {
- if (sensors::g_sensors != nullptr)
+ if (sensors::g_sensors != nullptr) {
errx(0, "already running");
+ }
sensors::g_sensors = new Sensors;
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != sensors::g_sensors->start()) {
delete sensors::g_sensors;
@@ -1621,8 +1731,9 @@ int sensors_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "not running");
+ }
delete sensors::g_sensors;
sensors::g_sensors = nullptr;
@@ -1641,4 +1752,3 @@ int sensors_main(int argc, char *argv[])
warnx("unrecognized command");
return 1;
}
-
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index 1c889a811..225570fa4 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -447,6 +447,7 @@ public:
QUAD_WIDE, /**< quad in wide configuration */
HEX_X, /**< hex in X configuration */
HEX_PLUS, /**< hex in + configuration */
+ HEX_COX,
OCTA_X,
OCTA_PLUS,
OCTA_COX,
@@ -516,7 +517,7 @@ private:
float _roll_scale;
float _pitch_scale;
float _yaw_scale;
- float _deadband;
+ float _idle_speed;
unsigned _rotor_count;
const Rotor *_rotors;
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index bf77795d5..092c0e2b0 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -67,6 +67,11 @@
namespace
{
+float constrain(float val, float min, float max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
/*
* These tables automatically generated by multi_tables - do not edit.
*/
@@ -110,6 +115,14 @@ const MultirotorMixer::Rotor _config_hex_plus[] = {
{ 0.866025, 0.500000, 1.00 },
{ -0.866025, -0.500000, -1.00 },
};
+const MultirotorMixer::Rotor _config_hex_cox[] = {
+ { -0.866025, 0.500000, -1.00 },
+ { -0.866025, 0.500000, 1.00 },
+ { -0.000000, -1.000000, -1.00 },
+ { -0.000000, -1.000000, 1.00 },
+ { 0.866025, 0.500000, -1.00 },
+ { 0.866025, 0.500000, 1.00 },
+};
const MultirotorMixer::Rotor _config_octa_x[] = {
{ -0.382683, 0.923880, -1.00 },
{ 0.382683, -0.923880, -1.00 },
@@ -147,6 +160,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_wide[0],
&_config_hex_x[0],
&_config_hex_plus[0],
+ &_config_hex_cox[0],
&_config_octa_x[0],
&_config_octa_plus[0],
&_config_octa_cox[0],
@@ -158,6 +172,7 @@ const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_wide */
6, /* hex_x */
6, /* hex_plus */
+ 6, /* hex_cox */
8, /* octa_x */
8, /* octa_plus */
8, /* octa_cox */
@@ -171,12 +186,12 @@ MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
float roll_scale,
float pitch_scale,
float yaw_scale,
- float deadband) :
+ float idle_speed) :
Mixer(control_cb, cb_handle),
_roll_scale(roll_scale),
_pitch_scale(pitch_scale),
_yaw_scale(yaw_scale),
- _deadband(-1.0f + deadband), /* shift to output range here to avoid runtime calculation */
+ _idle_speed(-1.0f + idle_speed * 2.0f), /* shift to output range here to avoid runtime calculation */
_rotor_count(_config_rotor_count[geometry]),
_rotors(_config_index[geometry])
{
@@ -247,6 +262,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "6x")) {
geometry = MultirotorMixer::HEX_X;
+ } else if (!strcmp(geomname, "6c")) {
+ geometry = MultirotorMixer::HEX_COX;
+
} else if (!strcmp(geomname, "8+")) {
geometry = MultirotorMixer::OCTA_PLUS;
@@ -276,67 +294,67 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
unsigned
MultirotorMixer::mix(float *outputs, unsigned space)
{
- float roll = get_control(0, 0) * _roll_scale;
+ float roll = constrain(get_control(0, 0) * _roll_scale, -1.0f, 1.0f);
//lowsyslog("roll: %d, get_control0: %d, %d\n", (int)(roll), (int)(get_control(0, 0)), (int)(_roll_scale));
- float pitch = get_control(0, 1) * _pitch_scale;
- float yaw = get_control(0, 2) * _yaw_scale;
- float thrust = get_control(0, 3);
+ float pitch = constrain(get_control(0, 1) * _pitch_scale, -1.0f, 1.0f);
+ float yaw = constrain(get_control(0, 2) * _yaw_scale, -1.0f, 1.0f);
+ float thrust = constrain(get_control(0, 3), 0.0f, 1.0f);
//lowsyslog("thrust: %d, get_control3: %d\n", (int)(thrust), (int)(get_control(0, 3)));
- float max = 0.0f;
- float fixup_scale;
+ float min_out = 0.0f;
+ float max_out = 0.0f;
+ float scale_yaw = 1.0f;
- /* use an output factor to prevent too strong control signals at low throttle */
- float min_thrust = 0.05f;
- float max_thrust = 1.0f;
- float startpoint_full_control = 0.40f;
- float output_factor;
+ /* perform initial mix pass yielding unbounded outputs, ignore yaw */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ float out = roll * _rotors[i].roll_scale +
+ pitch * _rotors[i].pitch_scale +
+ thrust;
- /* keep roll, pitch and yaw control to 0 below min thrust */
- if (thrust <= min_thrust) {
- output_factor = 0.0f;
- /* linearly increase the output factor from 0 to 1 between min_thrust and startpoint_full_control */
+ /* limit yaw if it causes outputs clipping */
+ if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) {
+ yaw = -out / _rotors[i].yaw_scale;
+ }
- } else if (thrust < startpoint_full_control && thrust > min_thrust) {
- output_factor = (thrust / max_thrust) / (startpoint_full_control - min_thrust);
- /* and then stay at full control */
+ /* calculate min and max output values */
+ if (out < min_out) {
+ min_out = out;
+ }
+ if (out > max_out) {
+ max_out = out;
+ }
- } else {
- output_factor = max_thrust;
+ outputs[i] = out;
}
- roll *= output_factor;
- pitch *= output_factor;
- yaw *= output_factor;
-
-
- /* perform initial mix pass yielding un-bounded outputs */
- for (unsigned i = 0; i < _rotor_count; i++) {
- float tmp = roll * _rotors[i].roll_scale +
- pitch * _rotors[i].pitch_scale +
- yaw * _rotors[i].yaw_scale +
- thrust;
+ /* scale down roll/pitch controls if some outputs are negative, don't add yaw, keep total thrust */
+ if (min_out < 0.0) {
+ float scale_in = thrust / (thrust - min_out);
- if (tmp > max)
- max = tmp;
+ /* mix again with adjusted controls */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] = scale_in * (roll * _rotors[i].roll_scale + pitch * _rotors[i].pitch_scale) + thrust;
+ }
- outputs[i] = tmp;
+ } else {
+ /* roll/pitch mixed without limiting, add yaw control */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] += yaw * _rotors[i].yaw_scale;
+ }
}
- /* scale values into the -1.0 - 1.0 range */
- if (max > 1.0f) {
- fixup_scale = 2.0f / max;
+ /* scale down all outputs if some outputs are too large, reduce total thrust */
+ float scale_out;
+ if (max_out > 1.0f) {
+ scale_out = 1.0f / max_out;
} else {
- fixup_scale = 2.0f;
+ scale_out = 1.0f;
}
- for (unsigned i = 0; i < _rotor_count; i++)
- outputs[i] = -1.0f + (outputs[i] * fixup_scale);
-
- /* ensure outputs are out of the deadband */
- for (unsigned i = 0; i < _rotor_count; i++)
- if (outputs[i] < _deadband)
- outputs[i] = _deadband;
+ /* scale outputs to range _idle_speed..1, and do final limiting */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] = constrain(_idle_speed + (outputs[i] * (1.0f - _idle_speed) * scale_out), _idle_speed, 1.0f);
+ }
return _rotor_count;
}
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
index 050bf2f47..b5698036e 100755
--- a/src/modules/systemlib/mixer/multi_tables
+++ b/src/modules/systemlib/mixer/multi_tables
@@ -52,6 +52,15 @@ set hex_plus {
120 CW
}
+set hex_cox {
+ 60 CW
+ 60 CCW
+ 180 CW
+ 180 CCW
+ -60 CW
+ -60 CCW
+}
+
set octa_x {
22.5 CW
-157.5 CW
@@ -85,7 +94,7 @@ set octa_cox {
-135 CW
}
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
+set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus hex_cox octa_x octa_plus octa_cox}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
@@ -104,13 +113,13 @@ foreach table $tables {
puts "};"
}
-puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
+puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::MAX_GEOMETRY\] = {"
foreach table $tables {
puts [format "\t&_config_%s\[0\]," $table]
}
puts "};"
-puts "const unsigned _config_rotor_count\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
+puts "const unsigned _config_rotor_count\[MultirotorMixer::MAX_GEOMETRY\] = {"
foreach table $tables {
upvar #0 $table angles
puts [format "\t%u, /* %s */" [expr [llength $angles] / 2] $table]
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index 2d773fd25..7a499ca72 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -521,73 +521,15 @@ param_save_default(void)
return ERROR;
}
- if (res == OK) {
- res = param_export(fd, false);
+ res = param_export(fd, false);
- if (res != OK) {
- warnx("failed to write parameters to file: %s", filename);
- }
+ if (res != OK) {
+ warnx("failed to write parameters to file: %s", filename);
}
close(fd);
return res;
-
-#if 0
- const char *filename_tmp = malloc(strlen(filename) + 5);
- sprintf(filename_tmp, "%s.tmp", filename);
-
- /* delete temp file if exist */
- res = unlink(filename_tmp);
-
- if (res != OK && errno == ENOENT)
- res = OK;
-
- if (res != OK)
- warn("failed to delete temp file: %s", filename_tmp);
-
- if (res == OK) {
- /* write parameters to temp file */
- fd = open(filename_tmp, O_WRONLY | O_CREAT | O_EXCL);
-
- if (fd < 0) {
- warn("failed to open temp file: %s", filename_tmp);
- res = ERROR;
- }
-
- if (res == OK) {
- res = param_export(fd, false);
-
- if (res != OK)
- warnx("failed to write parameters to file: %s", filename_tmp);
- }
-
- close(fd);
- }
-
- if (res == OK) {
- /* delete parameters file */
- res = unlink(filename);
-
- if (res != OK && errno == ENOENT)
- res = OK;
-
- if (res != OK)
- warn("failed to delete parameters file: %s", filename);
- }
-
- if (res == OK) {
- /* rename temp file to parameters */
- res = rename(filename_tmp, filename);
-
- if (res != OK)
- warn("failed to rename %s to %s", filename_tmp, filename);
- }
-
- free(filename_tmp);
-
- return res;
-#endif
}
/**
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index b4ca0ed3e..22182e39e 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -282,12 +282,18 @@ perf_reset(perf_counter_t handle)
void
perf_print_counter(perf_counter_t handle)
{
+ perf_print_counter_fd(0, handle);
+}
+
+void
+perf_print_counter_fd(int fd, perf_counter_t handle)
+{
if (handle == NULL)
return;
switch (handle->type) {
case PC_COUNT:
- printf("%s: %llu events\n",
+ dprintf(fd, "%s: %llu events\n",
handle->name,
((struct perf_ctr_count *)handle)->event_count);
break;
@@ -295,7 +301,7 @@ perf_print_counter(perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- printf("%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
handle->name,
pce->event_count,
pce->time_total,
@@ -308,7 +314,7 @@ perf_print_counter(perf_counter_t handle)
case PC_INTERVAL: {
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
- printf("%s: %llu events, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n",
handle->name,
pci->event_count,
(pci->time_last - pci->time_first) / pci->event_count,
@@ -349,12 +355,12 @@ perf_event_count(perf_counter_t handle)
}
void
-perf_print_all(void)
+perf_print_all(int fd)
{
perf_counter_t handle = (perf_counter_t)sq_peek(&perf_counters);
while (handle != NULL) {
- perf_print_counter(handle);
+ perf_print_counter_fd(fd, handle);
handle = (perf_counter_t)sq_next(&handle->link);
}
}
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index d8f69fdbf..6835ee4a2 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -121,16 +121,26 @@ __EXPORT extern void perf_cancel(perf_counter_t handle);
__EXPORT extern void perf_reset(perf_counter_t handle);
/**
- * Print one performance counter.
+ * Print one performance counter to stdout
*
* @param handle The counter to print.
*/
__EXPORT extern void perf_print_counter(perf_counter_t handle);
/**
+ * Print one performance counter to a fd.
+ *
+ * @param fd File descriptor to print to - e.g. 0 for stdout
+ * @param handle The counter to print.
+ */
+__EXPORT extern void perf_print_counter_fd(int fd, perf_counter_t handle);
+
+/**
* Print all of the performance counters.
+ *
+ * @param fd File descriptor to print to - e.g. 0 for stdout
*/
-__EXPORT extern void perf_print_all(void);
+__EXPORT extern void perf_print_all(int fd);
/**
* Reset all of the performance counters.
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 6a4e9392a..45f218a5b 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -53,7 +53,7 @@
#define SIGMA 0.000001f
-__EXPORT void pid_init(PID_t *pid, uint8_t mode, float dt_min)
+__EXPORT void pid_init(PID_t *pid, pid_mode_t mode, float dt_min)
{
pid->mode = mode;
pid->dt_min = dt_min;
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
index 190b315f1..ea5ba9e52 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.c
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -136,12 +136,26 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
}
effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
+
+ /* last line of defense against invalid inputs */
+ if (effective_pwm[i] < ramp_min_pwm) {
+ effective_pwm[i] = ramp_min_pwm;
+ } else if (effective_pwm[i] > max_pwm[i]) {
+ effective_pwm[i] = max_pwm[i];
+ }
}
}
break;
case PWM_LIMIT_STATE_ON:
for (unsigned i=0; i<num_channels; i++) {
effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+
+ /* last line of defense against invalid inputs */
+ if (effective_pwm[i] < min_pwm[i]) {
+ effective_pwm[i] = min_pwm[i];
+ } else if (effective_pwm[i] > max_pwm[i]) {
+ effective_pwm[i] = max_pwm[i];
+ }
}
break;
default:
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
index 21e15ec56..c0c1a5cb4 100644
--- a/src/modules/systemlib/rc_check.c
+++ b/src/modules/systemlib/rc_check.c
@@ -140,7 +140,7 @@ int rc_calibration_check(int mavlink_fd) {
/* sanity checks pass, enable channel */
if (count) {
mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
- warnx(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ warnx("ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
usleep(100000);
}
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index a23d89cd2..910b8a623 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -64,22 +64,40 @@ struct manual_control_setpoint_s {
/**
* Any of the channels may not be available and be set to NaN
* to indicate that it does not contain valid data.
+ * The variable names follow the definition of the
+ * MANUAL_CONTROL mavlink message.
+ * The default range is from -1 to 1 (mavlink message -1000 to 1000)
+ * The range for the z variable is defined from 0 to 1. (The z field of
+ * the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
*/
- float roll; /**< ailerons roll / roll rate input, -1..1 */
- float pitch; /**< elevator / pitch / pitch rate, -1..1 */
- float yaw; /**< rudder / yaw rate / yaw, -1..1 */
- float throttle; /**< throttle / collective thrust / altitude, 0..1 */
+ float x; /**< stick position in x direction -1..1
+ in general corresponds to forward/back motion or pitch of vehicle,
+ in general a positive value means forward or negative pitch and
+ a negative value means backward or positive pitch */
+ float y; /**< stick position in y direction -1..1
+ in general corresponds to right/left motion or roll of vehicle,
+ in general a positive value means right or positive roll and
+ a negative value means left or negative roll */
+ float z; /**< throttle stick position 0..1
+ in general corresponds to up/down motion or thrust of vehicle,
+ in general the value corresponds to the demanded throttle by the user,
+ if the input is used for setting the setpoint of a vertical position
+ controller any value > 0.5 means up and any value < 0.5 means down */
+ float r; /**< yaw stick/twist positon, -1..1
+ in general corresponds to the righthand rotation around the vertical
+ (downwards) axis of the vehicle */
float flaps; /**< flap position */
- float aux1; /**< default function: camera yaw / azimuth */
- float aux2; /**< default function: camera pitch / tilt */
- float aux3; /**< default function: camera trigger */
- float aux4; /**< default function: camera roll */
- float aux5; /**< default function: payload drop */
+ float aux1; /**< default function: camera yaw / azimuth */
+ float aux2; /**< default function: camera pitch / tilt */
+ float aux3; /**< default function: camera trigger */
+ float aux4; /**< default function: camera roll */
+ float aux5; /**< default function: payload drop */
- switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
- switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
- switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
+ switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
+ switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
+ switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
+ switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
+ switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index c168b2fac..370c54442 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -45,12 +45,12 @@
/**
* The number of RC channel inputs supported.
* Current (Q4/2013) radios support up to 18 channels,
- * leaving at a sane value of 15.
+ * leaving at a sane value of 16.
* This number can be greater then number of RC channels,
* because single RC channel can be mapped to multiple
* functions, e.g. for various mode switches.
*/
-#define RC_CHANNELS_MAPPED_MAX 15
+#define RC_CHANNELS_MAPPED_MAX 16
/**
* This defines the mapping of the RC functions.
@@ -64,15 +64,16 @@ enum RC_CHANNELS_FUNCTION {
YAW = 3,
MODE = 4,
RETURN = 5,
- ASSISTED = 6,
+ POSCTL = 6,
LOITER = 7,
OFFBOARD_MODE = 8,
- FLAPS = 9,
- AUX_1 = 10,
- AUX_2 = 11,
- AUX_3 = 12,
- AUX_4 = 13,
- AUX_5 = 14,
+ ACRO = 9,
+ FLAPS = 10,
+ AUX_1 = 11,
+ AUX_2 = 12,
+ AUX_3 = 13,
+ AUX_4 = 14,
+ AUX_5 = 15,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index a75810278..bbacb733a 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -68,6 +68,9 @@ struct vehicle_gps_position_s {
float eph; /**< GPS HDOP horizontal dilution of position in m */
float epv; /**< GPS VDOP horizontal dilution of position in m */
+ unsigned noise_per_ms; /**< */
+ unsigned jamming_indicator; /**< */
+
uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
float vel_m_s; /**< GPS ground speed (m/s) */
float vel_n_m_s; /**< GPS ground speed in m/s */
@@ -85,7 +88,7 @@ struct vehicle_gps_position_s {
uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
- uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
+ uint8_t satellite_snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
bool satellite_info_available; /**< 0 for no info, 1 for info available */
};
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index a15303ea4..5d39c897d 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -83,6 +83,8 @@ struct vehicle_local_position_s {
float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
+ float eph;
+ float epv;
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c6fe937ef..d902dc49e 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -61,9 +61,10 @@
/* main state machine */
typedef enum {
MAIN_STATE_MANUAL = 0,
- MAIN_STATE_SEATBELT,
- MAIN_STATE_EASY,
+ MAIN_STATE_ALTCTL,
+ MAIN_STATE_POSCTL,
MAIN_STATE_AUTO,
+ MAIN_STATE_ACRO,
MAIN_STATE_MAX
} main_state_t;
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
index e6d4b763b..4a97d328c 100644
--- a/src/systemcmds/config/config.c
+++ b/src/systemcmds/config/config.c
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
- * Author: Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012-2014 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
@@ -94,7 +92,6 @@ do_device(int argc, char *argv[])
}
int fd;
- int ret;
fd = open(argv[0], 0);
@@ -104,6 +101,8 @@ do_device(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[1], "block")) {
/* disable the device publications */
@@ -132,7 +131,6 @@ static void
do_gyro(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(GYRO_DEVICE_PATH, 0);
@@ -142,6 +140,8 @@ do_gyro(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the gyro internal sampling rate up to at least i Hz */
@@ -173,8 +173,13 @@ do_gyro(int argc, char *argv[])
warnx("gyro self test FAILED! Check calibration:");
struct gyro_scale scale;
ret = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(1, "failed getting gyro scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("gyro calibration and self test OK");
}
@@ -199,7 +204,6 @@ static void
do_mag(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(MAG_DEVICE_PATH, 0);
@@ -209,6 +213,8 @@ do_mag(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the mag internal sampling rate up to at least i Hz */
@@ -240,8 +246,13 @@ do_mag(int argc, char *argv[])
warnx("mag self test FAILED! Check calibration:");
struct mag_scale scale;
ret = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(ret, "failed getting mag scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("mag calibration and self test OK");
}
@@ -266,7 +277,6 @@ static void
do_accel(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(ACCEL_DEVICE_PATH, 0);
@@ -276,6 +286,8 @@ do_accel(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the accel internal sampling rate up to at least i Hz */
@@ -307,8 +319,13 @@ do_accel(int argc, char *argv[])
warnx("accel self test FAILED! Check calibration:");
struct accel_scale scale;
ret = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(ret, "failed getting accel scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("accel calibration and self test OK");
}
diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c
index e34be44e3..a3f9dffff 100644
--- a/src/systemcmds/mtd/24xxxx_mtd.c
+++ b/src/systemcmds/mtd/24xxxx_mtd.c
@@ -142,12 +142,9 @@ struct at24c_dev_s {
uint16_t pagesize; /* 32, 63 */
uint16_t npages; /* 128, 256, 512, 1024 */
- perf_counter_t perf_reads;
- perf_counter_t perf_writes;
- perf_counter_t perf_resets;
- perf_counter_t perf_read_retries;
- perf_counter_t perf_read_errors;
- perf_counter_t perf_write_errors;
+ perf_counter_t perf_transfers;
+ perf_counter_t perf_resets_retries;
+ perf_counter_t perf_errors;
};
/************************************************************************************
@@ -298,9 +295,9 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
for (;;) {
- perf_begin(priv->perf_reads);
+ perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
- perf_end(priv->perf_reads);
+ perf_end(priv->perf_transfers);
if (ret >= 0)
break;
@@ -314,10 +311,10 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
* XXX maybe do special first-read handling with optional
* bus reset as well?
*/
- perf_count(priv->perf_read_retries);
+ perf_count(priv->perf_resets_retries);
if (--tries == 0) {
- perf_count(priv->perf_read_errors);
+ perf_count(priv->perf_errors);
return ERROR;
}
}
@@ -383,9 +380,9 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
for (;;) {
- perf_begin(priv->perf_writes);
+ perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 1);
- perf_end(priv->perf_writes);
+ perf_end(priv->perf_transfers);
if (ret >= 0)
break;
@@ -397,7 +394,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
* poll for write completion.
*/
if (--tries == 0) {
- perf_count(priv->perf_write_errors);
+ perf_count(priv->perf_errors);
return ERROR;
}
}
@@ -521,12 +518,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
priv->mtd.ioctl = at24c_ioctl;
priv->dev = dev;
- priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read");
- priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write");
- priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset");
- priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries");
- priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors");
- priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors");
+ priv->perf_transfers = perf_alloc(PC_ELAPSED, "eeprom_trans");
+ priv->perf_resets_retries = perf_alloc(PC_COUNT, "eeprom_rst");
+ priv->perf_errors = perf_alloc(PC_COUNT, "eeprom_errs");
}
/* attempt to read to validate device is present */
@@ -548,9 +542,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
}
};
- perf_begin(priv->perf_reads);
+ perf_begin(priv->perf_transfers);
int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
- perf_end(priv->perf_reads);
+ perf_end(priv->perf_transfers);
if (ret < 0) {
return NULL;
diff --git a/src/systemcmds/mtd/mtd.c b/src/systemcmds/mtd/mtd.c
index 0a88d40f3..a57eaafe7 100644
--- a/src/systemcmds/mtd/mtd.c
+++ b/src/systemcmds/mtd/mtd.c
@@ -160,7 +160,11 @@ static void
ramtron_attach(void)
{
/* find the right spi */
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ struct spi_dev_s *spi = up_spiinitialize(4);
+#else
struct spi_dev_s *spi = up_spiinitialize(2);
+#endif
/* this resets the spi bus, set correct bus speed again */
SPI_SETFREQUENCY(spi, 10 * 1000 * 1000);
SPI_SETBITS(spi, 8);
diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk
index a48588535..b22b446da 100644
--- a/src/systemcmds/nshterm/module.mk
+++ b/src/systemcmds/nshterm/module.mk
@@ -38,4 +38,4 @@
MODULE_COMMAND = nshterm
SRCS = nshterm.c
-MODULE_STACKSIZE = 3000
+MODULE_STACKSIZE = 1200
diff --git a/src/systemcmds/param/module.mk b/src/systemcmds/param/module.mk
index 63f15ad28..f716eb71e 100644
--- a/src/systemcmds/param/module.mk
+++ b/src/systemcmds/param/module.mk
@@ -38,7 +38,8 @@
MODULE_COMMAND = param
SRCS = param.c
-MODULE_STACKSIZE = 4096
+# Note: measurements yielded a max of 900 bytes used.
+MODULE_STACKSIZE = 1800
MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c
index 0cbba0a37..d92ee88ef 100644
--- a/src/systemcmds/param/param.c
+++ b/src/systemcmds/param/param.c
@@ -61,8 +61,9 @@ static void do_load(const char* param_file_name);
static void do_import(const char* param_file_name);
static void do_show(const char* search_string);
static void do_show_print(void *arg, param_t param);
-static void do_set(const char* name, const char* val);
+static void do_set(const char* name, const char* val, bool fail_on_not_found);
static void do_compare(const char* name, const char* vals[], unsigned comparisons);
+static void do_reset();
int
param_main(int argc, char *argv[])
@@ -116,10 +117,17 @@ param_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "set")) {
- if (argc >= 4) {
- do_set(argv[2], argv[3]);
+ if (argc >= 5) {
+
+ /* if the fail switch is provided, fails the command if not found */
+ bool fail = !strcmp(argv[4], "fail");
+
+ do_set(argv[2], argv[3], fail);
+
+ } else if (argc >= 4) {
+ do_set(argv[2], argv[3], false);
} else {
- errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'");
+ errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3 [fail]'");
}
}
@@ -130,6 +138,10 @@ param_main(int argc, char *argv[])
errx(1, "not enough arguments.\nTry 'param compare PARAM_NAME 3'");
}
}
+
+ if (!strcmp(argv[1], "reset")) {
+ do_reset();
+ }
}
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'");
@@ -277,7 +289,7 @@ do_show_print(void *arg, param_t param)
}
static void
-do_set(const char* name, const char* val)
+do_set(const char* name, const char* val, bool fail_on_not_found)
{
int32_t i;
float f;
@@ -285,8 +297,8 @@ do_set(const char* name, const char* val)
/* set nothing if parameter cannot be found */
if (param == PARAM_INVALID) {
- /* param not found */
- errx(1, "Error: Parameter %s not found.", name);
+ /* param not found - fail silenty in scripts as it prevents booting */
+ errx(((fail_on_not_found) ? 1 : 0), "Error: Parameter %s not found.", name);
}
printf("%c %s: ",
@@ -402,3 +414,16 @@ do_compare(const char* name, const char* vals[], unsigned comparisons)
exit(ret);
}
+
+static void
+do_reset()
+{
+ param_reset_all();
+
+ if (param_save_default()) {
+ warnx("Param export failed.");
+ exit(1);
+ } else {
+ exit(0);
+ }
+}
diff --git a/src/systemcmds/perf/module.mk b/src/systemcmds/perf/module.mk
index 77952842b..ec39a7a85 100644
--- a/src/systemcmds/perf/module.mk
+++ b/src/systemcmds/perf/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = perf
SRCS = perf.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/perf/perf.c b/src/systemcmds/perf/perf.c
index b69ea597b..b08a2e3b7 100644
--- a/src/systemcmds/perf/perf.c
+++ b/src/systemcmds/perf/perf.c
@@ -73,7 +73,7 @@ int perf_main(int argc, char *argv[])
return -1;
}
- perf_print_all();
+ perf_print_all(0 /* stdout */);
fflush(stdout);
return 0;
}
diff --git a/src/systemcmds/preflight_check/module.mk b/src/systemcmds/preflight_check/module.mk
index 7c3c88783..0cb2a4cd0 100644
--- a/src/systemcmds/preflight_check/module.mk
+++ b/src/systemcmds/preflight_check/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check
SRCS = preflight_check.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk
index 4a23bba90..13a24150f 100644
--- a/src/systemcmds/pwm/module.mk
+++ b/src/systemcmds/pwm/module.mk
@@ -38,4 +38,4 @@
MODULE_COMMAND = pwm
SRCS = pwm.c
-MODULE_STACKSIZE = 4096
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/reboot/module.mk b/src/systemcmds/reboot/module.mk
index 19f64af54..edf9d8b37 100644
--- a/src/systemcmds/reboot/module.mk
+++ b/src/systemcmds/reboot/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = reboot
SRCS = reboot.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 800
diff --git a/src/systemcmds/tests/test_mtd.c b/src/systemcmds/tests/test_mtd.c
index bac9efbdb..cdb4362ba 100644
--- a/src/systemcmds/tests/test_mtd.c
+++ b/src/systemcmds/tests/test_mtd.c
@@ -57,6 +57,8 @@
#define PARAM_FILE_NAME "/fs/mtd_params"
static int check_user_abort(int fd);
+static void print_fail(void);
+static void print_success(void);
int check_user_abort(int fd) {
/* check if user wants to abort */
@@ -126,7 +128,7 @@ test_mtd(int argc, char *argv[])
uint8_t write_buf[chunk_sizes[c]] __attribute__((aligned(64)));
/* fill write buffer with known values */
- for (int i = 0; i < sizeof(write_buf); i++) {
+ for (unsigned i = 0; i < sizeof(write_buf); i++) {
/* this will wrap, but we just need a known value with spacing */
write_buf[i] = i+11;
}
@@ -137,11 +139,14 @@ test_mtd(int argc, char *argv[])
int fd = open(PARAM_FILE_NAME, O_RDONLY);
int rret = read(fd, read_buf, chunk_sizes[c]);
close(fd);
+ if (rret <= 0) {
+ err(1, "read error");
+ }
fd = open(PARAM_FILE_NAME, O_WRONLY);
printf("printing 2 percent of the first chunk:\n");
- for (int i = 0; i < sizeof(read_buf) / 50; i++) {
+ for (unsigned i = 0; i < sizeof(read_buf) / 50; i++) {
printf("%02X", read_buf[i]);
}
printf("\n");
@@ -171,9 +176,9 @@ test_mtd(int argc, char *argv[])
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
- int rret = read(fd, read_buf, chunk_sizes[c]);
+ int rret2 = read(fd, read_buf, chunk_sizes[c]);
- if (rret != chunk_sizes[c]) {
+ if (rret2 != (int)chunk_sizes[c]) {
warnx("READ ERROR!");
print_fail();
return 1;
@@ -182,7 +187,7 @@ test_mtd(int argc, char *argv[])
/* compare value */
bool compare_ok = true;
- for (int j = 0; j < chunk_sizes[c]; j++) {
+ for (unsigned j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d", j);
print_fail();
@@ -211,7 +216,7 @@ test_mtd(int argc, char *argv[])
char ffbuf[64];
memset(ffbuf, 0xFF, sizeof(ffbuf));
int fd = open(PARAM_FILE_NAME, O_WRONLY);
- for (int i = 0; i < file_size / sizeof(ffbuf); i++) {
+ for (unsigned i = 0; i < file_size / sizeof(ffbuf); i++) {
int ret = write(fd, ffbuf, sizeof(ffbuf));
if (ret != sizeof(ffbuf)) {
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index fe22f6177..e3f26924f 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -235,7 +235,7 @@ test_perf(int argc, char *argv[])
printf("perf: expect count of 1\n");
perf_print_counter(ec);
printf("perf: expect at least two counters\n");
- perf_print_all();
+ perf_print_all(0);
perf_free(cc);
perf_free(ec);
diff --git a/src/systemcmds/top/module.mk b/src/systemcmds/top/module.mk
index 9239aafc3..548a09f85 100644
--- a/src/systemcmds/top/module.mk
+++ b/src/systemcmds/top/module.mk
@@ -38,7 +38,7 @@
MODULE_COMMAND = top
SRCS = top.c
-MODULE_STACKSIZE = 3000
+MODULE_STACKSIZE = 1700
MAXOPTIMIZATION = -Os