aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-05-30 16:09:44 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-05-30 16:09:44 +0200
commitdc336a2ea4528489570e4eedb2b5102d699ad023 (patch)
tree0c9e189d5c9cc1b4f16d10c8ad44e9dec5a413ad
parente0042ec12cdccd157d181d5b9410fbeedfe3ce72 (diff)
parent90d8f7726d682e11039a313ebac6b047b59ccfb8 (diff)
downloadpx4-firmware-dc336a2ea4528489570e4eedb2b5102d699ad023.tar.gz
px4-firmware-dc336a2ea4528489570e4eedb2b5102d699ad023.tar.bz2
px4-firmware-dc336a2ea4528489570e4eedb2b5102d699ad023.zip
Merge remote-tracking branch 'upstream/master' into geo
-rw-r--r--ROMFS/px4fmu_common/init.d/10016_3dr_iris6
-rw-r--r--ROMFS/px4fmu_common/init.d/2100_mpx_easystar2
-rw-r--r--ROMFS/px4fmu_common/init.d/4008_ardrone25
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging2
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS8
-rw-r--r--ROMFS/px4fmu_common/mixers/README154
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--makefiles/config_px4fmu-v2_test.mk1
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk14
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig8
-rwxr-xr-xnuttx-configs/px4fmu-v2/include/board.h4
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig2
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h3
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h7
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c12
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c35
-rw-r--r--src/drivers/drv_io_expander.h (renamed from src/examples/flow_position_control/flow_position_control_params.h)93
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp10
-rw-r--r--src/drivers/gps/gps.cpp6
-rw-r--r--src/drivers/gps/gps_helper.cpp4
-rw-r--r--src/drivers/gps/gps_helper.h8
-rw-r--r--src/drivers/gps/ubx.cpp51
-rw-r--r--src/drivers/gps/ubx.h28
-rw-r--r--src/drivers/pca8574/module.mk6
-rw-r--r--src/drivers/pca8574/pca8574.cpp554
-rw-r--r--src/drivers/px4fmu/fmu.cpp9
-rw-r--r--src/drivers/px4io/px4io.cpp6
-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_control/module.mk41
-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/modules/commander/commander.cpp9
-rw-r--r--src/modules/commander/state_machine_helper.cpp4
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c4
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator.cpp2
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp61
-rw-r--r--src/modules/mavlink/mavlink_main.cpp11
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp46
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h7
-rw-r--r--src/modules/navigator/navigator_main.cpp2
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.c15
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.h2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c68
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c6
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h4
-rw-r--r--src/modules/px4iofirmware/mixer.cpp1
-rw-r--r--src/modules/sdlog2/sdlog2.c226
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h40
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp4
-rw-r--r--src/modules/systemlib/perf_counter.c16
-rw-r--r--src/modules/systemlib/perf_counter.h14
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c14
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h5
-rw-r--r--src/systemcmds/config/config.c43
-rw-r--r--src/systemcmds/perf/perf.c2
-rw-r--r--src/systemcmds/tests/test_mtd.c17
-rw-r--r--src/systemcmds/tests/tests_main.c2
62 files changed, 1481 insertions, 1057 deletions
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/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/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone
index 14786f210..e6007db0e 100644
--- a/ROMFS/px4fmu_common/init.d/4008_ardrone
+++ b/ROMFS/px4fmu_common/init.d/4008_ardrone
@@ -14,19 +14,20 @@ sh /etc/init.d/rc.mc_defaults
if [ $DO_AUTOCONFIG == yes ]
then
# Set all params here, then disable autoconfig
- param set MC_ROLL_P 5.0
- param set MC_ROLLRATE_P 0.13
- param set MC_ROLLRATE_I 0.0
- param set MC_ROLLRATE_D 0.0
- param set MC_PITCH_P 5.0
- param set MC_PITCHRATE_P 0.13
- param set MC_PITCHRATE_I 0.0
- param set MC_PITCHRATE_D 0.0
- param set MC_YAW_P 1.0
- param set MC_YAWRATE_P 0.15
- param set MC_YAWRATE_I 0.0
+ param set MC_ROLL_P 6.0
+ param set MC_ROLLRATE_P 0.14
+ param set MC_ROLLRATE_I 0.1
+ param set MC_ROLLRATE_D 0.002
+ param set MC_PITCH_P 6.0
+ param set MC_PITCHRATE_P 0.14
+ param set MC_PITCHRATE_I 0.1
+ param set MC_PITCHRATE_D 0.002
+ param set MC_YAW_P 2.0
+ param set MC_YAWRATE_P 0.2
+ param set MC_YAWRATE_I 0.2
param set MC_YAWRATE_D 0.0
- param set MC_YAW_FF 0.15
+ param set MC_YAW_FF 0.8
+
param set BAT_V_SCALING 0.00838095238
fi
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 517e073af..25f31a7e0 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -11,6 +11,6 @@ then
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/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 8c413e087..87ec4293e 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -93,14 +93,18 @@ then
#
if rgbled start
then
- echo "[init] Using external RGB Led"
+ echo "[init] RGB Led"
else
if blinkm start
then
- echo "[init] Using blinkm"
+ echo "[init] BlinkM"
blinkm systemstate
fi
fi
+
+ if pca8574 start
+ then
+ fi
#
# Set default values
diff --git a/ROMFS/px4fmu_common/mixers/README b/ROMFS/px4fmu_common/mixers/README
new file mode 100644
index 000000000..60311232e
--- /dev/null
+++ b/ROMFS/px4fmu_common/mixers/README
@@ -0,0 +1,154 @@
+PX4 mixer definitions
+=====================
+
+Files in this directory implement example mixers that can be used as a basis
+for customisation, or for general testing purposes.
+
+Mixer basics
+------------
+
+Mixers combine control values from various sources (control tasks, user inputs,
+etc.) and produce output values suitable for controlling actuators; servos,
+motors, switches and so on.
+
+An actuator derives its value from the combination of one or more control
+values. Each of the control values is scaled according to the actuator's
+configuration and then combined to produce the actuator value, which may then be
+further scaled to suit the specific output type.
+
+Internally, all scaling is performed using floating point values. Inputs and
+outputs are clamped to the range -1.0 to 1.0.
+
+control control control
+ | | |
+ v v v
+ scale scale scale
+ | | |
+ | v |
+ +-------> mix <------+
+ |
+ scale
+ |
+ v
+ out
+
+Scaling
+-------
+
+Basic scalers provide linear scaling of the input to the output.
+
+Each scaler allows the input value to be scaled independently for inputs
+greater/less than zero. An offset can be applied to the output, and lower and
+upper boundary constraints can be applied. Negative scaling factors cause the
+output to be inverted (negative input produces positive output).
+
+Scaler pseudocode:
+
+if (input < 0)
+ output = (input * NEGATIVE_SCALE) + OFFSET
+else
+ output = (input * POSITIVE_SCALE) + OFFSET
+
+if (output < LOWER_LIMIT)
+ output = LOWER_LIMIT
+if (output > UPPER_LIMIT)
+ output = UPPER_LIMIT
+
+Syntax
+------
+
+Mixer definitions are text files; lines beginning with a single capital letter
+followed by a colon are significant. All other lines are ignored, meaning that
+explanatory text can be freely mixed with the definitions.
+
+Each file may define more than one mixer; the allocation of mixers to actuators
+is specific to the device reading the mixer definition, and the number of
+actuator outputs generated by a mixer is specific to the mixer.
+
+A mixer begins with a line of the form
+
+ <tag>: <mixer arguments>
+
+The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a
+multirotor mixer, etc.
+
+Null Mixer
+..........
+
+A null mixer consumes no controls and generates a single actuator output whose
+value is always zero. Typically a null mixer is used as a placeholder in a
+collection of mixers in order to achieve a specific pattern of actuator outputs.
+
+The null mixer definition has the form:
+
+ Z:
+
+Simple Mixer
+............
+
+A simple mixer combines zero or more control inputs into a single actuator
+output. Inputs are scaled, and the mixing function sums the result before
+applying an output scaler.
+
+A simple mixer definition begins with:
+
+ M: <control count>
+ O: <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
+
+If <control count> is zero, the sum is effectively zero and the mixer will
+output a fixed value that is <offset> constrained by <lower limit> and <upper
+limit>.
+
+The second line defines the output scaler with scaler parameters as discussed
+above. Whilst the calculations are performed as floating-point operations, the
+values stored in the definition file are scaled by a factor of 10000; i.e. an
+offset of -0.5 is encoded as -5000.
+
+The definition continues with <control count> entries describing the control
+inputs and their scaling, in the form:
+
+ S: <group> <index> <-ve scale> <+ve scale> <offset> <lower limit> <upper limit>
+
+The <group> value identifies the control group from which the scaler will read,
+and the <index> value an offset within that group. These values are specific to
+the device reading the mixer definition.
+
+When used to mix vehicle controls, mixer group zero is the vehicle attitude
+control group, and index values zero through three are normally roll, pitch,
+yaw and thrust respectively.
+
+The remaining fields on the line configure the control scaler with parameters as
+discussed above. Whilst the calculations are performed as floating-point
+operations, the values stored in the definition file are scaled by a factor of
+10000; i.e. an offset of -0.5 is encoded as -5000.
+
+Multirotor Mixer
+................
+
+The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust)
+into a set of actuator outputs intended to drive motor speed controllers.
+
+The mixer definition is a single line of the form:
+
+R: <geometry> <roll scale> <pitch scale> <yaw scale> <deadband>
+
+The supported geometries include:
+
+ 4x - quadrotor in X configuration
+ 4+ - quadrotor in + configuration
+ 6x - hexcopter in X configuration
+ 6+ - hexcopter in + configuration
+ 8x - octocopter in X configuration
+ 8+ - octocopter in + configuration
+
+Each of the roll, pitch and yaw scale values determine scaling of the roll,
+pitch and yaw controls relative to the thrust control. Whilst the calculations
+are performed as floating-point operations, the values stored in the definition
+file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000.
+
+Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the
+thrust input ranges from 0.0 to 1.0. Output for each actuator is in the
+range -1.0 to 1.0.
+
+In the case where an actuator saturates, all actuator values are rescaled so that
+the saturating actuator is limited to 1.0. \ No newline at end of file
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index d6e88859c..a68cc32f4 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -40,6 +40,7 @@ MODULES += drivers/meas_airspeed
MODULES += drivers/frsky_telemetry
MODULES += modules/sensors
MODULES += drivers/mkblctrl
+MODULES += drivers/pca8574
# Needs to be burned to the ground and re-written; for now,
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 84274bf75..66b2157ed 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -24,6 +24,7 @@ MODULES += drivers/lsm303d
MODULES += drivers/l3gd20
MODULES += drivers/hmc5883
MODULES += drivers/ms5611
+MODULES += drivers/pca8574
MODULES += systemcmds/perf
MODULES += systemcmds/reboot
MODULES += systemcmds/tests
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/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index bc0c12067..f2c7d22bf 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -504,8 +504,8 @@ CONFIG_MTD_BYTE_WRITE=y
#
# USART1 Configuration
#
-CONFIG_USART1_RXBUFSIZE=256
-CONFIG_USART1_TXBUFSIZE=128
+CONFIG_USART1_RXBUFSIZE=300
+CONFIG_USART1_TXBUFSIZE=300
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=256
-CONFIG_UART5_TXBUFSIZE=128
+CONFIG_UART5_RXBUFSIZE=300
+CONFIG_UART5_TXBUFSIZE=300
CONFIG_UART5_BAUD=57600
CONFIG_UART5_BITS=8
CONFIG_UART5_PARITY=0
diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h
index 3bede8a1f..3b3c6fa70 100755
--- a/nuttx-configs/px4fmu-v2/include/board.h
+++ b/nuttx-configs/px4fmu-v2/include/board.h
@@ -268,6 +268,10 @@
#define GPIO_SPI2_MOSI (GPIO_SPI2_MOSI_1|GPIO_SPEED_50MHz)
#define GPIO_SPI2_SCK (GPIO_SPI2_SCK_2|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MISO (GPIO_SPI4_MISO_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_MOSI (GPIO_SPI4_MOSI_1|GPIO_SPEED_50MHz)
+#define GPIO_SPI4_SCK (GPIO_SPI4_SCK_1|GPIO_SPEED_50MHz)
+
/************************************************************************************
* Public Data
************************************************************************************/
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index a982040c6..7d5e6e9df 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -235,7 +235,7 @@ CONFIG_STM32_SDIO=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
# CONFIG_STM32_SPI3 is not set
-# CONFIG_STM32_SPI4 is not set
+CONFIG_STM32_SPI4=y
# CONFIG_STM32_SPI5 is not set
# CONFIG_STM32_SPI6 is not set
CONFIG_STM32_SYSCFG=y
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 58273f2d2..c944007a5 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -86,6 +86,7 @@ __BEGIN_DECLS
#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
+#define PX4_SPI_BUS_EXT 2
/*
* Use these in place of the spi_dev_e enumeration to
@@ -98,7 +99,7 @@ __BEGIN_DECLS
/*
* Optional devices on IO's external port
*/
-#define PX4_SPIDEV_ACCEL_MAG 2
+#define PX4_SPIDEV_ACCEL_MAG 2
/*
* I2C busses
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index c2de1bfba..36eb7bec4 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -106,8 +106,11 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#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 GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
+#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
#define PX4_SPI_BUS_SENSORS 1
+#define PX4_SPI_BUS_EXT 4
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
@@ -115,6 +118,10 @@ __BEGIN_DECLS
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
+/* External bus */
+#define PX4_SPIDEV_EXT0 1
+#define PX4_SPIDEV_EXT1 2
+
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_LED 2
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index 71414d62c..bf41bb1fe 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -192,6 +192,7 @@ stm32_boardinitialize(void)
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
+static struct spi_dev_s *spi4;
static struct sdio_dev_s *sdio;
#include <math.h>
@@ -305,6 +306,17 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
+ spi4 = up_spiinitialize(4);
+
+ /* Default SPI4 to 1MHz and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi4, 10000000);
+ SPI_SETBITS(spi4, 8);
+ SPI_SETMODE(spi4, SPIDEV_MODE3);
+ SPI_SELECT(spi4, PX4_SPIDEV_EXT0, false);
+ SPI_SELECT(spi4, PX4_SPIDEV_EXT1, false);
+
+ message("[boot] Initialized SPI port 4\n");
+
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index c66c490a7..01dbd6e77 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -94,6 +94,13 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_configgpio(GPIO_SPI_CS_FRAM);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
#endif
+
+#ifdef CONFIG_STM32_SPI4
+ stm32_configgpio(GPIO_SPI_CS_EXT0);
+ stm32_configgpio(GPIO_SPI_CS_EXT1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+#endif
}
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
@@ -157,3 +164,31 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
return SPI_STATUS_PRESENT;
}
#endif
+
+__EXPORT void stm32_spi4select(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_EXT0:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ break;
+
+ case PX4_SPIDEV_EXT1:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ break;
+
+ default:
+ break;
+
+ }
+}
+
+__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
diff --git a/src/examples/flow_position_control/flow_position_control_params.h b/src/drivers/drv_io_expander.h
index d0c8fc722..106354377 100644
--- a/src/examples/flow_position_control/flow_position_control_params.h
+++ b/src/drivers/drv_io_expander.h
@@ -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) 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
@@ -33,68 +31,41 @@
*
****************************************************************************/
+/**
+ * @file drv_io_expander.h
+ *
+ * IO expander device API
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <sys/ioctl.h>
+
/*
- * @file flow_position_control_params.h
- *
- * Parameters for position controller
+ * ioctl() definitions
*/
-#include <systemlib/param/param.h>
+#define _IOXIOCBASE (0x2800)
+#define _IOXIOC(_n) (_IOC(_IOXIOCBASE, _n))
-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;
-};
+/** set a bitmask (non-blocking) */
+#define IOX_SET_MASK _IOXIOC(1)
-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;
-};
+/** get a bitmask (blocking) */
+#define IOX_GET_MASK _IOXIOC(2)
-/**
- * Initialize all parameter handles and values
- *
- */
-int parameters_init(struct flow_position_control_param_handles *h);
+/** set device mode (non-blocking) */
+#define IOX_SET_MODE _IOXIOC(3)
-/**
- * Update all parameters
- *
- */
-int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p);
+/** set constant values (non-blocking) */
+#define IOX_SET_VALUE _IOXIOC(4)
+
+/* ... to IOX_SET_VALUE + 8 */
+
+/* enum passed to RGBLED_SET_MODE ioctl()*/
+enum IOX_MODE {
+ IOX_MODE_OFF,
+ IOX_MODE_ON,
+ IOX_MODE_TEST_OUT
+};
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/gps/gps.cpp b/src/drivers/gps/gps.cpp
index 6195cd6ea..5342ccf78 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -448,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_m, _report.epv_m);
+ warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m);
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/ubx.cpp b/src/drivers/gps/ubx.cpp
index 8a2afecb7..7502809bd 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;
}
@@ -440,8 +447,8 @@ UBX::handle_message()
gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer;
_gps_position->fix_type = packet->gpsFix;
- _gps_position->s_variance_m_s = packet->sAcc;
- _gps_position->p_variance_m = packet->pAcc;
+ _gps_position->s_variance_m_s = (float)packet->sAcc * 1e-2f; // from cm/s to m/s
+ _gps_position->p_variance_m = (float)packet->pAcc * 1e-2f; // from cm to m
_gps_position->timestamp_variance = hrt_absolute_time();
ret = 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/pca8574/module.mk b/src/drivers/pca8574/module.mk
new file mode 100644
index 000000000..825ee9bb7
--- /dev/null
+++ b/src/drivers/pca8574/module.mk
@@ -0,0 +1,6 @@
+#
+# PCA8574 driver for RGB LED
+#
+
+MODULE_COMMAND = pca8574
+SRCS = pca8574.cpp
diff --git a/src/drivers/pca8574/pca8574.cpp b/src/drivers/pca8574/pca8574.cpp
new file mode 100644
index 000000000..904ce18e8
--- /dev/null
+++ b/src/drivers/pca8574/pca8574.cpp
@@ -0,0 +1,554 @@
+/****************************************************************************
+ *
+ * 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
+ * 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 pca8574.cpp
+ *
+ * Driver for an 8 I/O controller (PC8574) connected via I2C.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <nuttx/config.h>
+
+#include <drivers/device/i2c.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <ctype.h>
+
+#include <nuttx/wqueue.h>
+
+#include <systemlib/perf_counter.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+
+#include <board_config.h>
+
+#include <drivers/drv_io_expander.h>
+
+#define PCA8574_ONTIME 120
+#define PCA8574_OFFTIME 120
+#define PCA8574_DEVICE_PATH "/dev/pca8574"
+
+#define ADDR 0x20 ///< I2C adress of PCA8574 (default, A0-A2 pulled to GND)
+
+class PCA8574 : public device::I2C
+{
+public:
+ PCA8574(int bus, int pca8574);
+ virtual ~PCA8574();
+
+
+ virtual int init();
+ virtual int probe();
+ virtual int info();
+ virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
+ bool is_running() { return _running; }
+
+private:
+ work_s _work;
+
+ uint8_t _values_out;
+ uint8_t _values_in;
+ uint8_t _blinking;
+ uint8_t _blink_phase;
+
+ enum IOX_MODE _mode;
+ bool _running;
+ int _led_interval;
+ bool _should_run;
+ bool _update_out;
+ int _counter;
+
+ static void led_trampoline(void *arg);
+ void led();
+
+ int send_led_enable(uint8_t arg);
+ int send_led_values();
+
+ int get(uint8_t &vals);
+};
+
+/* for now, we only support one PCA8574 */
+namespace
+{
+PCA8574 *g_pca8574;
+}
+
+void pca8574_usage();
+
+extern "C" __EXPORT int pca8574_main(int argc, char *argv[]);
+
+PCA8574::PCA8574(int bus, int pca8574) :
+ I2C("pca8574", PCA8574_DEVICE_PATH, bus, pca8574, 100000),
+ _values_out(0),
+ _values_in(0),
+ _blinking(0),
+ _blink_phase(0),
+ _mode(IOX_MODE_OFF),
+ _running(false),
+ _led_interval(80),
+ _should_run(false),
+ _update_out(false),
+ _counter(0)
+{
+ memset(&_work, 0, sizeof(_work));
+}
+
+PCA8574::~PCA8574()
+{
+}
+
+int
+PCA8574::init()
+{
+ int ret;
+ ret = I2C::init();
+
+ if (ret != OK) {
+ return ret;
+ }
+
+ return OK;
+}
+
+int
+PCA8574::probe()
+{
+ uint8_t val;
+ return get(val);
+}
+
+int
+PCA8574::info()
+{
+ int ret = OK;
+
+ return ret;
+}
+
+int
+PCA8574::ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int ret = ENOTTY;
+
+ switch (cmd) {
+ case IOX_SET_VALUE ...(IOX_SET_VALUE + 8): {
+ // set the specified on / off state
+ uint8_t position = (1 << (cmd - IOX_SET_VALUE));
+ uint8_t prev = _values_out;
+
+ if (arg) {
+ _values_out |= position;
+
+ } else {
+ _values_out &= ~(position);
+ }
+
+ if (_values_out != prev) {
+ if (_values_out) {
+ _mode = IOX_MODE_ON;
+ }
+ send_led_values();
+ }
+
+ return OK;
+ }
+
+ case IOX_SET_MASK:
+ send_led_enable(arg);
+ return OK;
+
+ case IOX_GET_MASK: {
+ uint8_t val;
+ ret = get(val);
+
+ if (ret == OK) {
+ return val;
+
+ } else {
+ return -1;
+ }
+ }
+
+ case IOX_SET_MODE:
+
+ if (_mode != (IOX_MODE)arg) {
+
+ switch ((IOX_MODE)arg) {
+ case IOX_MODE_OFF:
+ _values_out = 0xFF;
+ break;
+
+ case IOX_MODE_ON:
+ _values_out = 0;
+ break;
+
+ case IOX_MODE_TEST_OUT:
+ break;
+
+ default:
+ return -1;
+ }
+
+ _mode = (IOX_MODE)arg;
+ send_led_values();
+ }
+
+ return OK;
+
+ default:
+ // see if the parent class can make any use of it
+ ret = CDev::ioctl(filp, cmd, arg);
+ break;
+ }
+
+ return ret;
+}
+
+
+void
+PCA8574::led_trampoline(void *arg)
+{
+ PCA8574 *rgbl = reinterpret_cast<PCA8574 *>(arg);
+
+ rgbl->led();
+}
+
+/**
+ * Main loop function
+ */
+void
+PCA8574::led()
+{
+ if (_mode == IOX_MODE_TEST_OUT) {
+
+ // we count only seven states
+ _counter &= 0xF;
+ _counter++;
+
+ for (int i = 0; i < 8; i++) {
+ if (i < _counter) {
+ _values_out |= (1 << i);
+
+ } else {
+ _values_out &= ~(1 << i);
+ }
+ }
+
+ _update_out = true;
+ _should_run = true;
+ } else if (_mode == IOX_MODE_OFF) {
+ _update_out = true;
+ _should_run = false;
+ } else {
+
+ // Any of the normal modes
+ if (_blinking > 0) {
+ /* we need to be running to blink */
+ _should_run = true;
+ } else {
+ _should_run = false;
+ }
+ }
+
+ if (_update_out) {
+ uint8_t msg;
+
+ if (_blinking) {
+ msg = (_values_out & _blinking & _blink_phase);
+
+ // wipe out all positions that are marked as blinking
+ msg &= ~(_blinking);
+
+ // fill blink positions
+ msg |= ((_blink_phase) ? _blinking : 0);
+
+ _blink_phase = !_blink_phase;
+ } else {
+ msg = _values_out;
+ }
+
+ int ret = transfer(&msg, sizeof(msg), nullptr, 0);
+
+ if (!ret) {
+ _update_out = false;
+ }
+ }
+
+ // check if any activity remains, else stp
+ if (!_should_run) {
+ _running = false;
+ return;
+ }
+
+ // re-queue ourselves to run again later
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA8574::led_trampoline, this, _led_interval);
+}
+
+/**
+ * Sent ENABLE flag to LED driver
+ */
+int
+PCA8574::send_led_enable(uint8_t arg)
+{
+
+ int ret = transfer(&arg, sizeof(arg), nullptr, 0);
+
+ return ret;
+}
+
+/**
+ * Send 8 outputs
+ */
+int
+PCA8574::send_led_values()
+{
+ _update_out = true;
+
+ // if not active, kick it
+ if (!_running) {
+ _running = true;
+ work_queue(LPWORK, &_work, (worker_t)&PCA8574::led_trampoline, this, 1);
+ }
+
+ return 0;
+}
+
+int
+PCA8574::get(uint8_t &vals)
+{
+ uint8_t result;
+ int ret;
+
+ ret = transfer(nullptr, 0, &result, 1);
+
+ if (ret == OK) {
+ _values_in = result;
+ vals = result;
+ }
+
+ return ret;
+}
+
+void
+pca8574_usage()
+{
+ warnx("missing command: try 'start', 'test', 'info', 'off', 'stop', 'val 0 1'");
+ warnx("options:");
+ warnx(" -b i2cbus (%d)", PX4_I2C_BUS_LED);
+ warnx(" -a addr (0x%x)", ADDR);
+}
+
+int
+pca8574_main(int argc, char *argv[])
+{
+ int i2cdevice = -1;
+ int pca8574adr = ADDR; // 7bit
+
+ int ch;
+
+ // jump over start/off/etc and look at options first
+ while ((ch = getopt(argc, argv, "a:b:")) != EOF) {
+ switch (ch) {
+ case 'a':
+ pca8574adr = strtol(optarg, NULL, 0);
+ break;
+
+ case 'b':
+ i2cdevice = strtol(optarg, NULL, 0);
+ break;
+
+ default:
+ pca8574_usage();
+ exit(0);
+ }
+ }
+
+ if (optind >= argc) {
+ pca8574_usage();
+ exit(1);
+ }
+
+ const char *verb = argv[optind];
+
+ int fd;
+ int ret;
+
+ if (!strcmp(verb, "start")) {
+ if (g_pca8574 != nullptr) {
+ errx(1, "already started");
+ }
+
+ if (i2cdevice == -1) {
+ // try the external bus first
+ i2cdevice = PX4_I2C_BUS_EXPANSION;
+ g_pca8574 = new PCA8574(PX4_I2C_BUS_EXPANSION, pca8574adr);
+
+ if (g_pca8574 != nullptr && OK != g_pca8574->init()) {
+ delete g_pca8574;
+ g_pca8574 = nullptr;
+ }
+
+ if (g_pca8574 == nullptr) {
+ // fall back to default bus
+ if (PX4_I2C_BUS_LED == PX4_I2C_BUS_EXPANSION) {
+ errx(1, "init failed");
+ }
+
+ i2cdevice = PX4_I2C_BUS_LED;
+ }
+ }
+
+ if (g_pca8574 == nullptr) {
+ g_pca8574 = new PCA8574(i2cdevice, pca8574adr);
+
+ if (g_pca8574 == nullptr) {
+ errx(1, "new failed");
+ }
+
+ if (OK != g_pca8574->init()) {
+ delete g_pca8574;
+ g_pca8574 = nullptr;
+ errx(1, "init failed");
+ }
+ }
+
+ exit(0);
+ }
+
+ // need the driver past this point
+ if (g_pca8574 == nullptr) {
+ warnx("not started, run pca8574 start");
+ exit(1);
+ }
+
+ if (!strcmp(verb, "test")) {
+ fd = open(PCA8574_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA8574_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_TEST_OUT);
+
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "info")) {
+ g_pca8574->info();
+ exit(0);
+ }
+
+ if (!strcmp(verb, "off")) {
+ fd = open(PCA8574_DEVICE_PATH, 0);
+
+ if (fd < 0) {
+ errx(1, "Unable to open " PCA8574_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
+ close(fd);
+ exit(ret);
+ }
+
+ if (!strcmp(verb, "stop")) {
+ fd = open(PCA8574_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA8574_DEVICE_PATH);
+ }
+
+ ret = ioctl(fd, IOX_SET_MODE, (unsigned long)IOX_MODE_OFF);
+ close(fd);
+
+ // wait until we're not running any more
+ for (unsigned i = 0; i < 15; i++) {
+ if (!g_pca8574->is_running()) {
+ break;
+ }
+
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+ fflush(stdout);
+
+ if (!g_pca8574->is_running()) {
+ delete g_pca8574;
+ g_pca8574 = nullptr;
+ exit(0);
+ } else {
+ warnx("stop failed.");
+ exit(1);
+ }
+ }
+
+ if (!strcmp(verb, "val")) {
+ if (argc < 4) {
+ errx(1, "Usage: pca8574 val <channel> <0 or 1>");
+ }
+
+ fd = open(PCA8574_DEVICE_PATH, 0);
+
+ if (fd == -1) {
+ errx(1, "Unable to open " PCA8574_DEVICE_PATH);
+ }
+
+ unsigned channel = strtol(argv[2], NULL, 0);
+ unsigned val = strtol(argv[3], NULL, 0);
+
+ if (channel < 8) {
+ ret = ioctl(fd, (IOX_SET_VALUE + channel), val);
+ } else {
+ ret = -1;
+ }
+ close(fd);
+ exit(ret);
+ }
+
+ pca8574_usage();
+ exit(0);
+}
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index fd69cf795..8a4bfa18c 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -648,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
@@ -664,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 */
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 4099e5522..972f45148 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -581,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();
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_control/module.mk b/src/examples/flow_position_control/module.mk
deleted file mode 100644
index b10dc490a..000000000
--- a/src/examples/flow_position_control/module.mk
+++ /dev/null
@@ -1,41 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Build multirotor position control
-#
-
-MODULE_COMMAND = flow_position_control
-
-SRCS = flow_position_control_main.c \
- flow_position_control_params.c
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/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 76d32b442..3b27d1d52 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1246,10 +1246,10 @@ int commander_thread_main(int argc, char *argv[])
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 {
arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
@@ -1421,7 +1421,7 @@ int commander_thread_main(int argc, char *argv[])
home.alt = global_position.alt;
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) {
@@ -1861,7 +1861,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;
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index f1a353d5b..87309b238 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -138,7 +138,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current
// 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.");
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch first.");
}
valid_transition = false;
@@ -312,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;
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
index 1d9ae4623..8c82dd6c1 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
@@ -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 23ecd89ac..5db1adbb3 100644
--- a/src/modules/ekf_att_pos_estimator/estimator.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator.cpp
@@ -5,7 +5,7 @@
// Define EKF_DEBUG here to enable the debug print calls
// if the macro is not set, these will be completely
// optimized out by the compiler.
-#define EKF_DEBUG
+//#define EKF_DEBUG
#ifdef EKF_DEBUG
#include <stdio.h>
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 6943239e5..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 */
@@ -310,6 +312,8 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
/* 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;
}
@@ -755,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 */
@@ -773,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", (double)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,
@@ -782,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,
@@ -792,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);
+ }
}
/*
@@ -865,6 +907,7 @@ FixedwingAttitudeControl::task_main()
}
+ loop_counter++;
perf_end(_loop_perf);
}
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 28dd97fca..28cdf65a3 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -190,8 +190,9 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
/* check if there is space in the buffer, let it overflow else */
if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) {
- if (desired > buf_free) {
- desired = buf_free;
+ if (buf_free < desired) {
+ /* we don't want to send anything just in half, so return */
+ return;
}
}
@@ -222,6 +223,8 @@ Mavlink::Mavlink() :
_subscriptions(nullptr),
_streams(nullptr),
_mission_pub(-1),
+ _mode(MAVLINK_MODE_NORMAL),
+ _total_counter(0),
_verbose(false),
_forwarding_on(false),
_passing_on(false),
@@ -415,7 +418,7 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self)
void
Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self)
{
-
+
Mavlink *inst;
LL_FOREACH(_mavlink_instances, inst) {
if (inst != self) {
@@ -886,7 +889,7 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
switch (mavlink_mission_item->command) {
case MAV_CMD_NAV_TAKEOFF:
- mission_item->pitch_min = mavlink_mission_item->param2;
+ mission_item->pitch_min = mavlink_mission_item->param1;
break;
default:
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
index 2f45f2267..e1a6854b2 100644
--- a/src/modules/navigator/mission_feasibility_checker.cpp
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -63,7 +63,7 @@ MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capab
}
-bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Init if not done yet */
init();
@@ -76,24 +76,24 @@ bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_
if (isRotarywing)
- return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence);
+ return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence, home_alt);
else
- return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
+ return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence, home_alt);
}
-bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
- return checkGeofence(dm_current, nMissionItems, geofence);
+ return (checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
-bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Update fixed wing navigation capabilites */
updateNavigationCapabilities();
// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
- return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence));
+ return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
@@ -109,7 +109,7 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return false;
}
- if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) { //xxx: handle relative altitude
+ if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
return false;
}
@@ -119,6 +119,36 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return true;
}
+bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error)
+{
+ /* Check if all all waypoints are above the home altitude, only return false if bool throw_error = true */
+ for (size_t i = 0; i < nMissionItems; i++) {
+ static struct mission_item_s missionitem;
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ if (throw_error) {
+ return false;
+ } else {
+ return true;
+ }
+ }
+
+ if (home_alt > missionitem.altitude) {
+ if (throw_error) {
+ mavlink_log_info(_mavlink_fd, "Waypoint %d below home", i);
+ return false;
+ } else {
+ mavlink_log_info(_mavlink_fd, "#audio: warning waypoint %d below home", i);
+ return true;
+ }
+ }
+ }
+
+ return true;
+}
+
bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems)
{
/* Go through all mission items and search for a landing waypoint
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
index f98e28462..96c9209d3 100644
--- a/src/modules/navigator/mission_feasibility_checker.h
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -61,14 +61,15 @@ private:
/* Checks for all airframes */
bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error = false);
/* Checks specific to fixedwing airframes */
- bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
void updateNavigationCapabilities();
/* Checks specific to rotarywing airframes */
- bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
public:
MissionFeasibilityChecker();
@@ -77,7 +78,7 @@ public:
/*
* Returns true if mission is feasible and false otherwise
*/
- bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
};
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 87c893079..401d50f7e 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -519,7 +519,7 @@ Navigator::offboard_mission_update(bool isrotaryWing)
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
- missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
+ missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence, _home_pos.alt);
_mission.set_offboard_dataman_id(offboard_mission.dataman_id);
diff --git a/src/modules/position_estimator_inav/inertial_filter.c b/src/modules/position_estimator_inav/inertial_filter.c
index 2f1b3c014..a36a4688d 100644
--- a/src/modules/position_estimator_inav/inertial_filter.c
+++ b/src/modules/position_estimator_inav/inertial_filter.c
@@ -9,15 +9,18 @@
#include "inertial_filter.h"
-void inertial_filter_predict(float dt, float x[3])
+void inertial_filter_predict(float dt, float x[2], float acc)
{
if (isfinite(dt)) {
- x[0] += x[1] * dt + x[2] * dt * dt / 2.0f;
- x[1] += x[2] * dt;
+ if (!isfinite(acc)) {
+ acc = 0.0f;
+ }
+ x[0] += x[1] * dt + acc * dt * dt / 2.0f;
+ x[1] += acc * dt;
}
}
-void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
+void inertial_filter_correct(float e, float dt, float x[2], int i, float w)
{
if (isfinite(e) && isfinite(w) && isfinite(dt)) {
float ewdt = e * w * dt;
@@ -25,10 +28,6 @@ void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
if (i == 0) {
x[1] += w * ewdt;
- x[2] += w * w * ewdt / 3.0;
-
- } else if (i == 1) {
- x[2] += w * ewdt;
}
}
}
diff --git a/src/modules/position_estimator_inav/inertial_filter.h b/src/modules/position_estimator_inav/inertial_filter.h
index 761c17097..cdeb4cfc6 100644
--- a/src/modules/position_estimator_inav/inertial_filter.h
+++ b/src/modules/position_estimator_inav/inertial_filter.h
@@ -8,6 +8,6 @@
#include <stdbool.h>
#include <drivers/drv_hrt.h>
-void inertial_filter_predict(float dt, float x[3]);
+void inertial_filter_predict(float dt, float x[3], float acc);
void inertial_filter_correct(float e, float dt, float x[3], int i, float w);
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 fdc3233e0..d7503e42d 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -168,15 +168,15 @@ int position_estimator_inav_main(int argc, char *argv[])
exit(1);
}
-void write_debug_log(const char *msg, float dt, float x_est[3], float y_est[3], float z_est[3], float x_est_prev[3], float y_est_prev[3], float z_est_prev[3], float corr_acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
+void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2], float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
{
FILE *f = fopen("/fs/microsd/inav.log", "a");
if (f) {
char *s = malloc(256);
- unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f %.5f] y_est=[%.5f %.5f %.5f] z_est=[%.5f %.5f %.5f] x_est_prev=[%.5f %.5f %.5f] y_est_prev=[%.5f %.5f %.5f] z_est_prev=[%.5f %.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2], z_est[0], z_est[1], z_est[2], x_est_prev[0], x_est_prev[1], x_est_prev[2], y_est_prev[0], y_est_prev[1], y_est_prev[2], z_est_prev[0], z_est_prev[1], z_est_prev[2]);
+ unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f] y_est=[%.5f %.5f] z_est=[%.5f %.5f] x_est_prev=[%.5f %.5f] y_est_prev=[%.5f %.5f] z_est_prev=[%.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], y_est[0], y_est[1], z_est[0], z_est[1], x_est_prev[0], x_est_prev[1], y_est_prev[0], y_est_prev[1], z_est_prev[0], z_est_prev[1]);
fwrite(s, 1, n, f);
- n = snprintf(s, 256, "\tacc_corr=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", corr_acc[0], corr_acc[1], corr_acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v);
+ n = snprintf(s, 256, "\tacc=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", acc[0], acc[1], acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v);
fwrite(s, 1, n, f);
free(s);
}
@@ -195,14 +195,14 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
mavlink_log_info(mavlink_fd, "[inav] started");
- float x_est[3] = { 0.0f, 0.0f, 0.0f };
- float y_est[3] = { 0.0f, 0.0f, 0.0f };
- float z_est[3] = { 0.0f, 0.0f, 0.0f };
+ float x_est[2] = { 0.0f, 0.0f }; // pos, vel
+ float y_est[2] = { 0.0f, 0.0f }; // pos, vel
+ float z_est[2] = { 0.0f, 0.0f }; // pos, vel
float eph = 1.0;
float epv = 1.0;
- float x_est_prev[3], y_est_prev[3], z_est_prev[3];
+ float x_est_prev[2], y_est_prev[2], z_est_prev[2];
memset(x_est_prev, 0, sizeof(x_est_prev));
memset(y_est_prev, 0, sizeof(y_est_prev));
memset(z_est_prev, 0, sizeof(z_est_prev));
@@ -241,7 +241,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
/* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */
- float corr_acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
+ float acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
float acc_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
float corr_baro = 0.0f; // D
float corr_gps[3][2] = {
@@ -341,8 +341,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
- baro_offset += sensor.baro_alt_meter;
- baro_init_cnt++;
+ if (isfinite(sensor.baro_alt_meter)) {
+ baro_offset += sensor.baro_alt_meter;
+ baro_init_cnt++;
+ }
} else {
wait_baro = false;
@@ -418,19 +420,17 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* transform acceleration vector from body frame to NED frame */
for (int i = 0; i < 3; i++) {
- accel_NED[i] = 0.0f;
+ acc[i] = 0.0f;
for (int j = 0; j < 3; j++) {
- accel_NED[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
+ acc[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
}
}
- corr_acc[0] = accel_NED[0] - x_est[2];
- corr_acc[1] = accel_NED[1] - y_est[2];
- corr_acc[2] = accel_NED[2] + CONSTANTS_ONE_G - z_est[2];
+ acc[2] += CONSTANTS_ONE_G;
} else {
- memset(corr_acc, 0, sizeof(corr_acc));
+ memset(acc, 0, sizeof(acc));
}
accel_timestamp = sensor.accelerometer_timestamp;
@@ -628,11 +628,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* set position estimate to (0, 0, 0), use GPS velocity for XY */
x_est[0] = 0.0f;
x_est[1] = gps.vel_n_m_s;
- x_est[2] = accel_NED[0];
y_est[0] = 0.0f;
y_est[1] = gps.vel_e_m_s;
z_est[0] = 0.0f;
- y_est[2] = accel_NED[1];
local_pos.ref_lat = lat;
local_pos.ref_lon = lon;
@@ -655,10 +653,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (reset_est) {
x_est[0] = gps_proj[0];
x_est[1] = gps.vel_n_m_s;
- x_est[2] = accel_NED[0];
y_est[0] = gps_proj[1];
y_est[1] = gps.vel_e_m_s;
- y_est[2] = accel_NED[1];
}
/* calculate correction for position */
@@ -796,26 +792,26 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
c += att.R[j][i] * accel_bias_corr[j];
}
- acc_bias[i] += c * params.w_acc_bias * dt;
+ if (isfinite(c)) {
+ acc_bias[i] += c * params.w_acc_bias * dt;
+ }
}
/* inertial filter prediction for altitude */
- inertial_filter_predict(dt, z_est);
+ inertial_filter_predict(dt, z_est, acc[2]);
- if (!(isfinite(z_est[0]) && isfinite(z_est[1]) && isfinite(z_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER Z PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER Z PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(z_est, z_est_prev, sizeof(z_est));
}
/* inertial filter correction for altitude */
inertial_filter_correct(corr_baro, dt, z_est, 0, params.w_z_baro);
inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
- inertial_filter_correct(corr_acc[2], dt, z_est, 2, params.w_z_acc);
- if (!(isfinite(z_est[0]) && isfinite(z_est[1]) && isfinite(z_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(z_est, z_est_prev, sizeof(z_est));
- memset(corr_acc, 0, sizeof(corr_acc));
memset(corr_gps, 0, sizeof(corr_gps));
corr_baro = 0;
@@ -825,19 +821,16 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (can_estimate_xy) {
/* inertial filter prediction for position */
- inertial_filter_predict(dt, x_est);
- inertial_filter_predict(dt, y_est);
+ inertial_filter_predict(dt, x_est, acc[0]);
+ inertial_filter_predict(dt, y_est, acc[1]);
- if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(x_est[2]) && isfinite(y_est[0]) && isfinite(y_est[1]) && isfinite(y_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(y_est[0]) && isfinite(y_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(x_est, x_est_prev, sizeof(x_est));
memcpy(y_est, y_est_prev, sizeof(y_est));
}
/* inertial filter correction for position */
- inertial_filter_correct(corr_acc[0], dt, x_est, 2, params.w_xy_acc);
- inertial_filter_correct(corr_acc[1], dt, y_est, 2, params.w_xy_acc);
-
if (use_flow) {
inertial_filter_correct(corr_flow[0], dt, x_est, 1, params.w_xy_flow * w_flow);
inertial_filter_correct(corr_flow[1], dt, y_est, 1, params.w_xy_flow * w_flow);
@@ -853,11 +846,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(x_est[2]) && isfinite(y_est[0]) && isfinite(y_est[1]) && isfinite(y_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(y_est[0]) && isfinite(y_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(x_est, x_est_prev, sizeof(x_est));
memcpy(y_est, y_est_prev, sizeof(y_est));
- memset(corr_acc, 0, sizeof(corr_acc));
memset(corr_gps, 0, sizeof(corr_gps));
memset(corr_flow, 0, sizeof(corr_flow));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index 2e4f26661..8aa08b6f2 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -42,11 +42,9 @@
PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
-PARAM_DEFINE_FLOAT(INAV_W_Z_ACC, 20.0f);
PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
-PARAM_DEFINE_FLOAT(INAV_W_XY_ACC, 20.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
@@ -62,11 +60,9 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
- h->w_z_acc = param_find("INAV_W_Z_ACC");
h->w_z_sonar = param_find("INAV_W_Z_SONAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
- h->w_xy_acc = param_find("INAV_W_XY_ACC");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
@@ -85,11 +81,9 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
{
param_get(h->w_z_baro, &(p->w_z_baro));
param_get(h->w_z_gps_p, &(p->w_z_gps_p));
- param_get(h->w_z_acc, &(p->w_z_acc));
param_get(h->w_z_sonar, &(p->w_z_sonar));
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
- param_get(h->w_xy_acc, &(p->w_xy_acc));
param_get(h->w_xy_flow, &(p->w_xy_flow));
param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index e2be079d3..08ec996a1 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -43,11 +43,9 @@
struct position_estimator_inav_params {
float w_z_baro;
float w_z_gps_p;
- float w_z_acc;
float w_z_sonar;
float w_xy_gps_p;
float w_xy_gps_v;
- float w_xy_acc;
float w_xy_flow;
float w_gps_flow;
float w_acc_bias;
@@ -63,11 +61,9 @@ struct position_estimator_inav_params {
struct position_estimator_inav_param_handles {
param_t w_z_baro;
param_t w_z_gps_p;
- param_t w_z_acc;
param_t w_z_sonar;
param_t w_xy_gps_p;
param_t w_xy_gps_v;
- param_t w_xy_acc;
param_t w_xy_flow;
param_t w_gps_flow;
param_t w_acc_bias;
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/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 70ce76806..577cadfbb 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,7 @@ 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;
}
}
@@ -387,7 +423,58 @@ 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);
+ 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;
+ }
+ }
+
+ 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);
@@ -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,7 +778,7 @@ 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);
@@ -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,8 +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_GSN0_s log_GSN0;
- struct log_GSN1_s log_GSN1;
+ 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)
@@ -969,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;
@@ -983,19 +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);
- /* log the SNR of each satellite for a detailed view of signal quality */
- log_msg.msg_type = LOG_GSN0_MSG;
- /* pick the smaller number so we do not overflow any of the arrays */
- 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_GSN0.satellite_snr) / sizeof(log_msg.body.log_GSN0.satellite_snr[0]);
- unsigned sat_max_snr = (gps_msg_max_snr < log_max_snr) ? gps_msg_max_snr : log_max_snr;
+ 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;
- for (unsigned i = 0; i < sat_max_snr; i++) {
- log_msg.body.log_GSN0.satellite_snr[i] = buf_gps_pos.satellite_snr[i];
+ /* 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);
}
- LOGBUFFER_WRITE_AND_COUNT(GSN0);
}
/* --- SENSOR COMBINED --- */
@@ -1340,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 90025b9ff..f4d88f079 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -139,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)--- */
@@ -318,16 +322,28 @@ struct log_VICN_s {
float yaw;
};
-/* --- GSN0 - GPS SNR #0 --- */
-#define LOG_GSN0_MSG 26
-struct log_GSN0_s {
- uint8_t satellite_snr[16]; /**< Signal to noise ratio of satellite. 0 for none, 255 for max. */
+/* --- 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 */
};
-/* --- GSN1 - GPS SNR #1 --- */
-#define LOG_GSN1_MSG 27
-struct log_GSN1_s {
- uint8_t satellite_snr[16]; /**< Signal to noise ratio of satellite. 0 for none, 255 for max. */
+/* --- 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 **********/
@@ -363,7 +379,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
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"),
@@ -381,8 +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(GSN0, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
- LOG_FORMAT(GSN1, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ 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/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 4ad21d818..092c0e2b0 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -351,9 +351,9 @@ MultirotorMixer::mix(float *outputs, unsigned space)
scale_out = 1.0f;
}
- /* scale outputs to range _idle_speed..1 */
+ /* scale outputs to range _idle_speed..1, and do final limiting */
for (unsigned i = 0; i < _rotor_count; i++) {
- outputs[i] = _idle_speed + (outputs[i] * (1.0f - _idle_speed) * scale_out);
+ 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/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/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/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 794c3f8bc..5924a324d 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_m; /**< GPS HDOP horizontal dilution of position in m */
float epv_m; /**< 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/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/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/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);