aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
m---------NuttX0
-rw-r--r--README.md5
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps9
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.logging2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.mc_apps5
-rwxr-xr-xTools/px_uploader.py53
-rw-r--r--makefiles/config_px4fmu-v2_default.mk1
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk2
-rw-r--r--msg/vehicle_attitude.msg17
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/defconfig6
-rw-r--r--nuttx-configs/px4fmu-v2/nsh/defconfig6
-rw-r--r--src/drivers/drv_mag.h2
-rw-r--r--src/drivers/gps/gps_helper.cpp2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp8
-rw-r--r--src/drivers/hmc5883/hmc5883_i2c.cpp5
-rw-r--r--src/drivers/hmc5883/hmc5883_spi.cpp5
-rw-r--r--src/drivers/ms5611/ms5611.h12
-rw-r--r--src/drivers/px4fmu/fmu.cpp11
-rw-r--r--src/drivers/px4io/px4io.cpp45
-rw-r--r--src/lib/mathlib/math/filter/LowPassFilter2p.cpp5
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp38
-rw-r--r--src/modules/commander/commander.cpp184
-rw-r--r--src/modules/commander/mag_calibration.cpp79
-rw-r--r--src/modules/dataman/dataman.c2
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp94
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_21states.cpp2142
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_21states.h247
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_22states.cpp (renamed from src/modules/ekf_att_pos_estimator/estimator_23states.cpp)986
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_22states.h (renamed from src/modules/ekf_att_pos_estimator/estimator_23states.h)42
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk2
-rw-r--r--src/modules/land_detector/FixedwingLandDetector.cpp125
-rw-r--r--src/modules/land_detector/FixedwingLandDetector.h105
-rw-r--r--src/modules/land_detector/LandDetector.cpp124
-rw-r--r--src/modules/land_detector/LandDetector.h104
-rw-r--r--src/modules/land_detector/MulticopterLandDetector.cpp145
-rw-r--r--src/modules/land_detector/MulticopterLandDetector.h116
-rw-r--r--src/modules/land_detector/land_detector_main.cpp214
-rw-r--r--src/modules/land_detector/land_detector_params.c104
-rw-r--r--src/modules/land_detector/module.mk13
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp21
-rw-r--r--src/modules/mavlink/mavlink_receiver.h3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c34
-rw-r--r--src/modules/px4iofirmware/controls.c9
-rw-r--r--src/modules/sdlog2/sdlog2.c30
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h17
-rw-r--r--src/modules/sensors/sensor_params.c6
-rw-r--r--src/modules/sensors/sensors.cpp4
-rw-r--r--src/modules/systemlib/err.c3
-rw-r--r--src/modules/uORB/objects_common.cpp3
-rw-r--r--src/modules/uORB/topics/vehicle_land_detected.h63
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h1
-rw-r--r--src/modules/uORB/topics/vtol_vehicle_status.h1
-rw-r--r--src/modules/uORB/uORB.cpp16
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_main.cpp104
-rw-r--r--src/modules/vtol_att_control/vtol_att_control_params.c35
-rw-r--r--src/systemcmds/config/config.c6
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c11
57 files changed, 2166 insertions, 3268 deletions
diff --git a/NuttX b/NuttX
-Subproject dbcccb2455d759b789d549d25e1fbf489b2d3c8
+Subproject 574bac488f384ddaa344378e25653c27124a2b6
diff --git a/README.md b/README.md
index 33b8cdec7..db125e06d 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
## PX4 Flight Control Stack and Middleware ##
-[![Build Status](https://travis-ci.org/PX4/Firmware.svg?branch=master)](https://travis-ci.org/PX4/Firmware)
+[![Build Status](https://travis-ci.org/PX4/Firmware.svg?branch=master)](https://travis-ci.org/PX4/Firmware) [![Coverity Scan](https://scan.coverity.com/projects/3966/badge.svg?flat=1)](https://scan.coverity.com/projects/3966?tab=overview)
[![Gitter](https://badges.gitter.im/Join%20Chat.svg)](https://gitter.im/PX4/Firmware?utm_source=badge&utm_medium=badge&utm_campaign=pr-badge&utm_content=badge)
@@ -21,7 +21,8 @@ Please refer to the [user documentation](https://pixhawk.org/users/start) for fl
### Developers ###
Contributing guide:
-http://px4.io/dev/contributing
+ * [CONTRIBUTING.md](https://github.com/PX4/Firmware/blob/master/CONTRIBUTING.md)
+ * [PX4 Contribution Guide](http://px4.io/dev/contributing)
Developer guide:
http://px4.io/dev/
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 9aca3fc5f..9e2d1f6ff 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -13,3 +13,12 @@ ekf_att_pos_estimator start
#
fw_att_control start
fw_pos_control_l1 start
+
+#
+# Start Land Detector
+#
+land_detector start fixedwing
+
+#
+# Misc apps
+#
diff --git a/ROMFS/px4fmu_common/init.d/rc.logging b/ROMFS/px4fmu_common/init.d/rc.logging
index 25f31a7e0..a14eb5247 100644
--- a/ROMFS/px4fmu_common/init.d/rc.logging
+++ b/ROMFS/px4fmu_common/init.d/rc.logging
@@ -8,7 +8,7 @@ then
if ver hwcmp PX4FMU_V1
then
echo "Start sdlog2 at 50Hz"
- sdlog2 start -r 50 -a -b 4 -t
+ sdlog2 start -r 40 -a -b 3 -t
else
echo "Start sdlog2 at 200Hz"
sdlog2 start -r 200 -a -b 22 -t
diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_apps b/ROMFS/px4fmu_common/init.d/rc.mc_apps
index 2248b0bcd..7b29fb3a7 100644
--- a/ROMFS/px4fmu_common/init.d/rc.mc_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.mc_apps
@@ -15,3 +15,8 @@ else
mc_att_control_m start
fi
mc_pos_control start
+
+#
+# Start Land Detector
+#
+land_detector start multicopter
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index c46f6bede..95a3d4046 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -266,18 +266,19 @@ class uploader(object):
self.__getSync()
return value
- def __drawProgressBar(self, progress, maxVal):
+ def __drawProgressBar(self, label, progress, maxVal):
if maxVal < progress:
progress = maxVal
percent = (float(progress) / float(maxVal)) * 100.0
- sys.stdout.write("\rprogress:[%-20s] %.2f%%" % ('='*int(percent/5.0), percent))
+ sys.stdout.write("\r%s: [%-20s] %.1f%%" % (label, '='*int(percent/5.0), percent))
sys.stdout.flush()
# send the CHIP_ERASE command and wait for the bootloader to become ready
- def __erase(self):
+ def __erase(self, label):
+ print("\n", end='')
self.__send(uploader.CHIP_ERASE
+ uploader.EOC)
@@ -288,15 +289,14 @@ class uploader(object):
#Draw progress bar (erase usually takes about 9 seconds to complete)
estimatedTimeRemaining = deadline-time.time()
if estimatedTimeRemaining >= 9.0:
- self.__drawProgressBar(20.0-estimatedTimeRemaining, 9.0)
+ self.__drawProgressBar(label, 20.0-estimatedTimeRemaining, 9.0)
else:
- self.__drawProgressBar(10.0, 10.0)
+ self.__drawProgressBar(label, 10.0, 10.0)
sys.stdout.write(" (timeout: %d seconds) " % int(deadline-time.time()) )
sys.stdout.flush()
if self.__trySync():
- self.__drawProgressBar(10.0, 10.0)
- sys.stdout.write("\nerase complete!\n")
+ self.__drawProgressBar(label, 10.0, 10.0)
return;
raise RuntimeError("timed out waiting for erase")
@@ -350,7 +350,8 @@ class uploader(object):
return [seq[i:i+length] for i in range(0, len(seq), length)]
# upload code
- def __program(self, fw):
+ def __program(self, label, fw):
+ print("\n", end='')
code = fw.image
groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
@@ -361,31 +362,40 @@ class uploader(object):
#Print upload progress (throttled, so it does not delay upload progress)
uploadProgress += 1
if uploadProgress % 256 == 0:
- self.__drawProgressBar(uploadProgress, len(groups))
- self.__drawProgressBar(100, 100)
- print("\nprogram complete!")
+ self.__drawProgressBar(label, uploadProgress, len(groups))
+ self.__drawProgressBar(label, 100, 100)
# verify code
- def __verify_v2(self, fw):
+ def __verify_v2(self, label, fw):
+ print("\n", end='')
self.__send(uploader.CHIP_VERIFY
+ uploader.EOC)
self.__getSync()
code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX)
+ verifyProgress = 0
for bytes in groups:
+ verifyProgress += 1
+ if verifyProgress % 256 == 0:
+ self.__drawProgressBar(label, verifyProgress, len(groups))
if (not self.__verify_multi(bytes)):
raise RuntimeError("Verification failed")
+ self.__drawProgressBar(label, 100, 100)
- def __verify_v3(self, fw):
- expect_crc = fw.crc(self.fw_maxsize)
+ def __verify_v3(self, label, fw):
+ print("\n", end='')
+ self.__drawProgressBar(label, 1, 100)
+ expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC
+ uploader.EOC)
report_crc = self.__recv_int()
self.__getSync()
+ verifyProgress = 0
if report_crc != expect_crc:
print("Expected 0x%x" % expect_crc)
print("Got 0x%x" % report_crc)
raise RuntimeError("Program CRC failed")
+ self.__drawProgressBar(label, 100, 100)
# get basic data about the board
def identify(self):
@@ -439,19 +449,16 @@ class uploader(object):
except Exception:
# ignore bad character encodings
pass
- print("erase...")
- self.__erase()
-
- print("program...")
- self.__program(fw)
+
+ self.__erase("Erase ")
+ self.__program("Program", fw)
- print("verify...")
if self.bl_rev == 2:
- self.__verify_v2(fw)
+ self.__verify_v2("Verify ", fw)
else:
- self.__verify_v3(fw)
+ self.__verify_v3("Verify ", fw)
- print("done, rebooting.")
+ print("\nRebooting.\n")
self.__reboot()
self.port.close()
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index a5f996bb3..aa2e01229 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -71,6 +71,7 @@ MODULES += modules/navigator
MODULES += modules/mavlink
MODULES += modules/gpio_led
MODULES += modules/uavcan
+MODULES += modules/land_detector
#
# Estimation modules (EKF/ SO3 / other filters)
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index ef70d51f2..396980453 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -50,7 +50,7 @@ OBJDUMP = $(CROSSDEV)objdump
# Check if the right version of the toolchain is available
#
-CROSSDEV_VER_SUPPORTED = 4.7.4 4.7.5 4.7.6 4.8.4
+CROSSDEV_VER_SUPPORTED = 4.7.4 4.7.5 4.7.6 4.8.4 4.9.3
CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion)
ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
diff --git a/msg/vehicle_attitude.msg b/msg/vehicle_attitude.msg
index dbfd8b6bc..98018a1df 100644
--- a/msg/vehicle_attitude.msg
+++ b/msg/vehicle_attitude.msg
@@ -16,20 +16,3 @@ float32[4] q # Quaternion (NED)
float32[3] g_comp # Compensated gravity vector
bool R_valid # Rotation matrix valid
bool q_valid # Quaternion valid
-
-# secondary attitude for VTOL
-float32 roll_sec # Roll angle (rad, Tait-Bryan, NED)
-float32 pitch_sec # Pitch angle (rad, Tait-Bryan, NED)
-float32 yaw_sec # Yaw angle (rad, Tait-Bryan, NED)
-float32 rollspeed_sec # Roll angular speed (rad/s, Tait-Bryan, NED)
-float32 pitchspeed_sec # Pitch angular speed (rad/s, Tait-Bryan, NED)
-float32 yawspeed_sec # Yaw angular speed (rad/s, Tait-Bryan, NED)
-float32 rollacc_sec # Roll angular accelration (rad/s, Tait-Bryan, NED)
-float32 pitchacc_sec # Pitch angular acceleration (rad/s, Tait-Bryan, NED)
-float32 yawacc_sec # Yaw angular acceleration (rad/s, Tait-Bryan, NED)
-float32[3] rate_offsets_sec # Offsets of the body angular rates from zero
-float32[9] R_sec # Rotation matrix, body to world, (Tait-Bryan, NED)
-float32[4] q_sec # Quaternion (NED)
-float32[3] g_comp_sec # Compensated gravity vector
-bool R_valid_sec # Rotation matrix valid
-bool q_valid_sec # Quaternion valid
diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig
index fade1f0c6..a467fa605 100644
--- a/nuttx-configs/px4fmu-v1/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v1/nsh/defconfig
@@ -417,7 +417,7 @@ CONFIG_PREALLOC_TIMERS=50
# Stack and heap information
#
CONFIG_IDLETHREAD_STACKSIZE=3500
-CONFIG_USERMAIN_STACKSIZE=3000
+CONFIG_USERMAIN_STACKSIZE=2600
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -719,11 +719,11 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=2048
+CONFIG_SCHED_WORKSTACKSIZE=1800
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=2048
+CONFIG_SCHED_LPWORKSTACKSIZE=1800
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig
index ac3dbe5da..9030a1f02 100644
--- a/nuttx-configs/px4fmu-v2/nsh/defconfig
+++ b/nuttx-configs/px4fmu-v2/nsh/defconfig
@@ -451,7 +451,7 @@ CONFIG_PREALLOC_TIMERS=50
# Stack and heap information
#
CONFIG_IDLETHREAD_STACKSIZE=3500
-CONFIG_USERMAIN_STACKSIZE=3000
+CONFIG_USERMAIN_STACKSIZE=2600
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_PTHREAD_STACK_DEFAULT=2048
@@ -797,11 +797,11 @@ CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WORKPRIORITY=192
CONFIG_SCHED_WORKPERIOD=5000
-CONFIG_SCHED_WORKSTACKSIZE=2000
+CONFIG_SCHED_WORKSTACKSIZE=1800
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKPERIOD=50000
-CONFIG_SCHED_LPWORKSTACKSIZE=2000
+CONFIG_SCHED_LPWORKSTACKSIZE=1800
# CONFIG_LIB_KBDCODEC is not set
# CONFIG_LIB_SLCDCODEC is not set
diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h
index 5ddf5d08e..d341e8947 100644
--- a/src/drivers/drv_mag.h
+++ b/src/drivers/drv_mag.h
@@ -41,9 +41,11 @@
#include <stdint.h>
#include <sys/ioctl.h>
+#include "drv_device.h"
#include "drv_sensor.h"
#include "drv_orb_dev.h"
+
#define MAG_DEVICE_PATH "/dev/mag"
/**
diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index 05dfc99b7..8157bc7e6 100644
--- a/src/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
@@ -88,8 +88,6 @@ GPS_Helper::set_baudrate(const int &fd, unsigned baud)
case 115200: speed = B115200; break;
- warnx("try baudrate: %d\n", speed);
-
default:
warnx("ERR: baudrate: %d\n", baud);
return -EINVAL;
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index 2a10b0063..95fbed0ba 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -66,6 +66,7 @@
#include <drivers/drv_mag.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/ringbuffer.h>
+#include <drivers/drv_device.h>
#include <uORB/uORB.h>
#include <uORB/topics/subsystem_info.h>
@@ -725,6 +726,9 @@ HMC5883::ioctl(struct file *filp, int cmd, unsigned long arg)
debug("MAGIOCGEXTERNAL in main driver");
return _interface->ioctl(cmd, dummy);
+ case DEVIOCGDEVICEID:
+ return _interface->ioctl(cmd, dummy);
+
default:
/* give it to the superclass */
return CDev::ioctl(filp, cmd, arg);
@@ -1305,9 +1309,9 @@ struct hmc5883_bus_option {
uint8_t busnum;
HMC5883 *dev;
} bus_options[] = {
- { HMC5883_BUS_I2C_INTERNAL, "/dev/hmc5883_int", &HMC5883_I2C_interface, PX4_I2C_BUS_EXPANSION, NULL },
+ { HMC5883_BUS_I2C_EXTERNAL, "/dev/hmc5883_ext", &HMC5883_I2C_interface, PX4_I2C_BUS_EXPANSION, NULL },
#ifdef PX4_I2C_BUS_ONBOARD
- { HMC5883_BUS_I2C_EXTERNAL, "/dev/hmc5883_ext", &HMC5883_I2C_interface, PX4_I2C_BUS_ONBOARD, NULL },
+ { HMC5883_BUS_I2C_INTERNAL, "/dev/hmc5883_int", &HMC5883_I2C_interface, PX4_I2C_BUS_ONBOARD, NULL },
#endif
#ifdef PX4_SPIDEV_HMC
{ HMC5883_BUS_SPI, "/dev/hmc5883_spi", &HMC5883_SPI_interface, PX4_SPI_BUS_SENSORS, NULL },
diff --git a/src/drivers/hmc5883/hmc5883_i2c.cpp b/src/drivers/hmc5883/hmc5883_i2c.cpp
index 782ea62fe..f86c1af6b 100644
--- a/src/drivers/hmc5883/hmc5883_i2c.cpp
+++ b/src/drivers/hmc5883/hmc5883_i2c.cpp
@@ -53,6 +53,7 @@
#include <drivers/device/i2c.h>
#include <drivers/drv_mag.h>
+#include <drivers/drv_device.h>
#include "hmc5883.h"
@@ -90,6 +91,7 @@ HMC5883_I2C_interface(int bus)
HMC5883_I2C::HMC5883_I2C(int bus) :
I2C("HMC5883_I2C", nullptr, bus, HMC5883L_ADDRESS, 400000)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
}
HMC5883_I2C::~HMC5883_I2C()
@@ -117,6 +119,9 @@ HMC5883_I2C::ioctl(unsigned operation, unsigned &arg)
return 0;
}
+ case DEVIOCGDEVICEID:
+ return CDev::ioctl(nullptr, operation, arg);
+
default:
ret = -EINVAL;
}
diff --git a/src/drivers/hmc5883/hmc5883_spi.cpp b/src/drivers/hmc5883/hmc5883_spi.cpp
index 25a2f2b40..aec990ca8 100644
--- a/src/drivers/hmc5883/hmc5883_spi.cpp
+++ b/src/drivers/hmc5883/hmc5883_spi.cpp
@@ -53,6 +53,7 @@
#include <drivers/device/spi.h>
#include <drivers/drv_mag.h>
+#include <drivers/drv_device.h>
#include "hmc5883.h"
#include <board_config.h>
@@ -92,6 +93,7 @@ HMC5883_SPI_interface(int bus)
HMC5883_SPI::HMC5883_SPI(int bus, spi_dev_e device) :
SPI("HMC5883_SPI", nullptr, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz */)
{
+ _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
}
HMC5883_SPI::~HMC5883_SPI()
@@ -146,6 +148,9 @@ HMC5883_SPI::ioctl(unsigned operation, unsigned &arg)
return 0;
}
+ case DEVIOCGDEVICEID:
+ return CDev::ioctl(nullptr, operation, arg);
+
default:
{
ret = -EINVAL;
diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h
index f0b3fd61d..3f1f6c473 100644
--- a/src/drivers/ms5611/ms5611.h
+++ b/src/drivers/ms5611/ms5611.h
@@ -37,12 +37,12 @@
* Shared defines for the ms5611 driver.
*/
-#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
-#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start temperature conversion */
-#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start pressure conversion */
-#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
-#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
-#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
+#define ADDR_RESET_CMD 0x1E /* write to this address to reset chip */
+#define ADDR_CMD_CONVERT_D1 0x48 /* write to this address to start pressure conversion */
+#define ADDR_CMD_CONVERT_D2 0x58 /* write to this address to start temperature conversion */
+#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
+#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
+#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
/* interface ioctls */
#define IOCTL_RESET 2
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 436672040..112c01513 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2012-2015 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
@@ -1637,12 +1637,15 @@ sensor_reset(int ms)
fd = open(PX4FMU_DEVICE_PATH, O_RDWR);
- if (fd < 0)
+ if (fd < 0) {
errx(1, "open fail");
+ }
- if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0)
- err(1, "servo arm failed");
+ if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0) {
+ warnx("sensor rail reset failed");
+ }
+ close(fd);
}
void
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 96ebedd83..1c9a5adc9 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
@@ -834,7 +834,7 @@ PX4IO::init()
_task = task_spawn_cmd("px4io",
SCHED_DEFAULT,
SCHED_PRIORITY_ACTUATOR_OUTPUTS,
- 2000,
+ 1800,
(main_t)&PX4IO::task_main_trampoline,
nullptr);
@@ -1102,7 +1102,7 @@ PX4IO::io_set_control_state(unsigned group)
uint16_t regs[_max_actuators];
/* get controls */
- bool changed;
+ bool changed = false;
switch (group) {
case 0:
@@ -1144,11 +1144,13 @@ PX4IO::io_set_control_state(unsigned group)
break;
}
- if (!changed)
+ if (!changed) {
return -1;
+ }
- for (unsigned i = 0; i < _max_controls; i++)
+ for (unsigned i = 0; i < _max_controls; i++) {
regs[i] = FLOAT_TO_REG(controls.control[i]);
+ }
/* copy values to registers in IO */
return io_reg_set(PX4IO_PAGE_CONTROLS, group * PX4IO_PROTOCOL_MAX_CONTROL_COUNT, regs, _max_controls);
@@ -1773,12 +1775,12 @@ PX4IO::print_debug()
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
int io_fd = -1;
- if (io_fd < 0) {
+ if (io_fd <= 0) {
io_fd = ::open("/dev/ttyS0", O_RDONLY | O_NONBLOCK | O_NOCTTY);
}
/* read IO's output */
- if (io_fd > 0) {
+ if (io_fd >= 0) {
pollfd fds[1];
fds[0].fd = io_fd;
fds[0].events = POLLIN;
@@ -2278,6 +2280,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
case PWM_SERVO_GET_DISABLE_LOCKDOWN:
*(unsigned *)arg = _lockdown_override;
+ break;
case PWM_SERVO_SET_FORCE_SAFETY_OFF:
/* force safety swith off */
@@ -3003,11 +3006,14 @@ monitor(void)
fds[0].fd = 0;
fds[0].events = POLLIN;
- poll(fds, 1, 2000);
+ if (poll(fds, 1, 2000) < 0) {
+ errx(1, "poll fail");
+ }
if (fds[0].revents == POLLIN) {
- int c;
- read(0, &c, 1);
+ /* control logic is to cancel with any key */
+ char c;
+ (void)read(0, &c, 1);
if (cancels-- == 0) {
printf("\033[2J\033[H"); /* move cursor home and clear screen */
@@ -3069,12 +3075,13 @@ lockdown(int argc, char *argv[])
if (ret > 0) {
- read(0, &c, 1);
+ if (read(0, &c, 1) > 0) {
- if (c != 'y') {
- exit(0);
- } else if (c == 'y') {
- break;
+ if (c != 'y') {
+ exit(0);
+ } else if (c == 'y') {
+ break;
+ }
}
}
@@ -3237,7 +3244,13 @@ px4io_main(int argc, char *argv[])
if (!strcmp(argv[1], "limit")) {
if ((argc > 2)) {
- g_dev->set_update_rate(atoi(argv[2]));
+ int limitrate = atoi(argv[2]);
+
+ if (limitrate > 0) {
+ g_dev->set_update_rate(limitrate);
+ } else {
+ errx(1, "invalid rate: %d", limitrate);
+ }
} else {
errx(1, "missing argument (50 - 500 Hz)");
diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.cpp b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp
index 6f640c9f9..c709a2834 100644
--- a/src/lib/mathlib/math/filter/LowPassFilter2p.cpp
+++ b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp
@@ -66,6 +66,7 @@ float LowPassFilter2p::apply(float sample)
// no filtering
return sample;
}
+
// do the filtering
float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2;
if (isnan(delay_element_0) || isinf(delay_element_0)) {
@@ -82,7 +83,9 @@ float LowPassFilter2p::apply(float sample)
}
float LowPassFilter2p::reset(float sample) {
- _delay_element_1 = _delay_element_2 = sample;
+ float dval = sample / (_b0 + _b1 + _b2);
+ _delay_element_1 = dval;
+ _delay_element_2 = dval;
return apply(sample);
}
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
index fd6bd0218..86f59f0e6 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -595,44 +595,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
memcpy(&att.R[0], &R.data[0][0], sizeof(att.R));
att.R_valid = true;
- // compute secondary attitude
- math::Matrix<3, 3> R_adapted; //modified rotation matrix
- R_adapted = R;
-
- //move z to x
- R_adapted(0, 0) = R(0, 2);
- R_adapted(1, 0) = R(1, 2);
- R_adapted(2, 0) = R(2, 2);
- //move x to z
- R_adapted(0, 2) = R(0, 0);
- R_adapted(1, 2) = R(1, 0);
- R_adapted(2, 2) = R(2, 0);
-
- //change direction of pitch (convert to right handed system)
- R_adapted(0, 0) = -R_adapted(0, 0);
- R_adapted(1, 0) = -R_adapted(1, 0);
- R_adapted(2, 0) = -R_adapted(2, 0);
- math::Vector<3> euler_angles_sec; //adapted euler angles for fixed wing operation
- euler_angles_sec = R_adapted.to_euler();
-
- att.roll_sec = euler_angles_sec(0);
- att.pitch_sec = euler_angles_sec(1);
- att.yaw_sec = euler_angles_sec(2);
-
- memcpy(&att.R_sec[0], &R_adapted.data[0][0], sizeof(att.R_sec));
-
- att.rollspeed_sec = -x_aposteriori[2];
- att.pitchspeed_sec = x_aposteriori[1];
- att.yawspeed_sec = x_aposteriori[0];
- att.rollacc_sec = -x_aposteriori[5];
- att.pitchacc_sec = x_aposteriori[4];
- att.yawacc_sec = x_aposteriori[3];
-
- att.g_comp_sec[0] = -raw.accelerometer_m_s2[2] - (-acc(2));
- att.g_comp_sec[1] = raw.accelerometer_m_s2[1] - acc(1);
- att.g_comp_sec[2] = raw.accelerometer_m_s2[0] - acc(0);
-
-
if (isfinite(att.roll) && isfinite(att.pitch) && isfinite(att.yaw)) {
// Broadcast
orb_publish(ORB_ID(vehicle_attitude), pub_att, &att);
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index f511f3876..247a2c5b8 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -84,6 +84,7 @@
#include <uORB/topics/geofence_result.h>
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/vtol_vehicle_status.h>
+ #include <uORB/topics/vehicle_land_detected.h>
#include <drivers/drv_led.h>
#include <drivers/drv_hrt.h>
@@ -241,6 +242,13 @@ transition_result_t check_navigation_state_machine(struct vehicle_status_s *stat
transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy);
/**
+* @brief This function initializes the home position of the vehicle. This happens first time we get a good GPS fix and each
+* time the vehicle is armed with a good GPS fix.
+**/
+static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home,
+ const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition);
+
+/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
*/
void *commander_low_prio_loop(void *arg);
@@ -560,7 +568,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
}
break;
- /* Flight termination */
+ /* Flight termination */
case VEHICLE_CMD_DO_FLIGHTTERMINATION: {
if (cmd->param1 > 0.5f) {
//XXX update state machine?
@@ -716,6 +724,53 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s
return true;
}
+/**
+* @brief This function initializes the home position of the vehicle. This happens first time we get a good GPS fix and each
+* time the vehicle is armed with a good GPS fix.
+**/
+static void commander_set_home_position(orb_advert_t &homePub, home_position_s &home,
+ const vehicle_local_position_s &localPosition, const vehicle_global_position_s &globalPosition)
+{
+ //Need global position fix to be able to set home
+ if (!status.condition_global_position_valid) {
+ return;
+ }
+
+ //Ensure that the GPS accuracy is good enough for intializing home
+ if (globalPosition.eph > eph_threshold || globalPosition.epv > epv_threshold) {
+ return;
+ }
+
+ //Set home position
+ home.timestamp = hrt_absolute_time();
+ home.lat = globalPosition.lat;
+ home.lon = globalPosition.lon;
+ home.alt = globalPosition.alt;
+
+ home.x = localPosition.x;
+ home.y = localPosition.y;
+ home.z = localPosition.z;
+
+ warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+
+ /* announce new home position */
+ if (homePub > 0) {
+ orb_publish(ORB_ID(home_position), homePub, &home);
+
+ } else {
+ homePub = orb_advertise(ORB_ID(home_position), &home);
+ }
+
+ //Play tune first time we initialize HOME
+ if (!status.condition_home_position_valid) {
+ tune_positive(true);
+ }
+
+ /* mark home position as set */
+ status.condition_home_position_valid = true;
+}
+
int commander_thread_main(int argc, char *argv[])
{
/* not yet initialized */
@@ -904,7 +959,6 @@ int commander_thread_main(int argc, char *argv[])
bool critical_battery_voltage_actions_done = false;
hrt_abstime last_idle_time = 0;
- hrt_abstime start_time = 0;
bool status_changed = true;
bool param_init_forced = true;
@@ -964,6 +1018,11 @@ int commander_thread_main(int argc, char *argv[])
struct vehicle_local_position_s local_position;
memset(&local_position, 0, sizeof(local_position));
+ /* Subscribe to land detector */
+ int land_detector_sub = orb_subscribe(ORB_ID(vehicle_land_detected));
+ struct vehicle_land_detected_s land_detector;
+ memset(&land_detector, 0, sizeof(land_detector));
+
/*
* The home position is set based on GPS only, to prevent a dependency between
* position estimator and commander. RAW GPS is more than good enough for a
@@ -1035,7 +1094,7 @@ int commander_thread_main(int argc, char *argv[])
commander_initialized = true;
thread_running = true;
- start_time = hrt_absolute_time();
+ const hrt_abstime commander_boot_timestamp = hrt_absolute_time();
transition_result_t arming_ret;
@@ -1096,8 +1155,8 @@ int commander_thread_main(int argc, char *argv[])
}
/* set vehicle_status.is_vtol flag */
- status.is_vtol = (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) ||
- (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
+ status.is_vtol = (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) ||
+ (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR);
/* check and update system / component ID */
param_get(_param_system_id, &(status.system_id));
@@ -1259,12 +1318,12 @@ int commander_thread_main(int argc, char *argv[])
}
//Notify the user if the status of the safety switch changes
- if(safety.safety_switch_available && previous_safety_off != safety.safety_off) {
+ if (safety.safety_switch_available && previous_safety_off != safety.safety_off) {
- if(safety.safety_off) {
+ if (safety.safety_off) {
set_tune(TONE_NOTIFY_POSITIVE_TUNE);
- }
- else {
+
+ } else {
tune_neutral(true);
}
@@ -1279,8 +1338,9 @@ int commander_thread_main(int argc, char *argv[])
/* vtol status changed */
orb_copy(ORB_ID(vtol_vehicle_status), vtol_vehicle_status_sub, &vtol_status);
status.vtol_fw_permanent_stab = vtol_status.fw_permanent_stab;
+
/* Make sure that this is only adjusted if vehicle realy is of type vtol*/
- if (status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR || VEHICLE_TYPE_VTOL_QUADROTOR) {
+ if ((status.system_type == VEHICLE_TYPE_VTOL_DUOROTOR) || (status.system_type == VEHICLE_TYPE_VTOL_QUADROTOR)) {
status.is_rotary_wing = vtol_status.vtol_in_rw_mode;
}
}
@@ -1325,34 +1385,6 @@ int commander_thread_main(int argc, char *argv[])
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid),
&status_changed);
- /* update home position */
- if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
- (global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) {
-
- home.lat = global_position.lat;
- home.lon = global_position.lon;
- home.alt = global_position.alt;
-
- home.x = local_position.x;
- home.y = local_position.y;
- home.z = local_position.z;
-
- warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
-
- /* announce new home position */
- if (home_pub > 0) {
- orb_publish(ORB_ID(home_position), home_pub, &home);
-
- } else {
- home_pub = orb_advertise(ORB_ID(home_position), &home);
- }
-
- /* mark home position as set */
- status.condition_home_position_valid = true;
- tune_positive(true);
- }
-
/* update condition_local_position_valid and condition_local_altitude_valid */
/* hysteresis for EPH */
bool local_eph_good;
@@ -1379,9 +1411,15 @@ int commander_thread_main(int argc, char *argv[])
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid,
&(status.condition_local_altitude_valid), &status_changed);
+ /* Update land detector */
+ orb_check(land_detector_sub, &updated);
+ if(updated) {
+ orb_copy(ORB_ID(vehicle_land_detected), land_detector_sub, &land_detector);
+ }
+
if (status.condition_local_altitude_valid) {
- if (status.condition_landed != local_position.landed) {
- status.condition_landed = local_position.landed;
+ if (status.condition_landed != land_detector.landed) {
+ status.condition_landed = land_detector.landed;
status_changed = true;
if (status.condition_landed) {
@@ -1401,7 +1439,7 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls);
/* only consider battery voltage if system has been running 2s and battery voltage is valid */
- if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) {
+ if (hrt_absolute_time() > commander_boot_timestamp + 2000000 && battery.voltage_filtered_v > 0.0f) {
status.battery_voltage = battery.voltage_filtered_v;
status.battery_current = battery.current_a;
status.condition_battery_voltage_valid = true;
@@ -1419,7 +1457,7 @@ int commander_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(subsystem_info), subsys_sub, &info);
- warnx("subsystem changed: %d\n", (int)info.subsystem_type);
+ //warnx("subsystem changed: %d\n", (int)info.subsystem_type);
/* mark / unmark as present */
if (info.present) {
@@ -1609,7 +1647,8 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",(hrt_absolute_time()-status.rc_signal_lost_timestamp)/1000);
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",
+ (hrt_absolute_time() - status.rc_signal_lost_timestamp) / 1000);
status_changed = true;
}
}
@@ -1710,9 +1749,9 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (!status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)",hrt_absolute_time()/1000);
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)", hrt_absolute_time() / 1000);
status.rc_signal_lost = true;
- status.rc_signal_lost_timestamp=sp_man.timestamp;
+ status.rc_signal_lost_timestamp = sp_man.timestamp;
status_changed = true;
}
}
@@ -1859,42 +1898,23 @@ int commander_thread_main(int argc, char *argv[])
}
}
+ //Get current timestamp
+ const hrt_abstime now = hrt_absolute_time();
- hrt_abstime t1 = hrt_absolute_time();
+ //First time home position update
+ if (!status.condition_home_position_valid) {
+ commander_set_home_position(home_pub, home, local_position, global_position);
+ }
+
+ /* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
+ else if (arming_state_changed && armed.armed && !was_armed && now > commander_boot_timestamp + 2000000) {
+ commander_set_home_position(home_pub, home, local_position, global_position);
+ }
/* print new state */
if (arming_state_changed) {
status_changed = true;
mavlink_log_info(mavlink_fd, "[cmd] arming state: %s", arming_states_str[status.arming_state]);
-
- /* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
- if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
- (global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) {
-
- // TODO remove code duplication
- home.lat = global_position.lat;
- home.lon = global_position.lon;
- home.alt = global_position.alt;
-
- home.x = local_position.x;
- home.y = local_position.y;
- home.z = local_position.z;
-
- warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
-
- /* announce new home position */
- if (home_pub > 0) {
- orb_publish(ORB_ID(home_position), home_pub, &home);
-
- } else {
- home_pub = orb_advertise(ORB_ID(home_position), &home);
- }
-
- /* mark home position as set */
- status.condition_home_position_valid = true;
- }
-
arming_state_changed = false;
}
@@ -1915,11 +1935,14 @@ int commander_thread_main(int argc, char *argv[])
if (status.failsafe != failsafe_old) {
status_changed = true;
+
if (status.failsafe) {
mavlink_log_critical(mavlink_fd, "failsafe mode on");
+
} else {
mavlink_log_critical(mavlink_fd, "failsafe mode off");
}
+
failsafe_old = status.failsafe;
}
@@ -1932,13 +1955,13 @@ int commander_thread_main(int argc, char *argv[])
/* publish states (armed, control mode, vehicle status) at least with 5 Hz */
if (counter % (200000 / COMMANDER_MONITORING_INTERVAL) == 0 || status_changed) {
set_control_mode();
- control_mode.timestamp = t1;
+ control_mode.timestamp = now;
orb_publish(ORB_ID(vehicle_control_mode), control_mode_pub, &control_mode);
- status.timestamp = t1;
+ status.timestamp = now;
orb_publish(ORB_ID(vehicle_status), status_pub, &status);
- armed.timestamp = t1;
+ armed.timestamp = now;
orb_publish(ORB_ID(actuator_armed), armed_pub, &armed);
}
@@ -1965,7 +1988,7 @@ int commander_thread_main(int argc, char *argv[])
if (!armed.armed || (safety.safety_switch_available && !safety.safety_off)) {
//Notify the user that it is safe to approach the vehicle
- if(arm_tune_played) {
+ if (arm_tune_played) {
tune_neutral(true);
}
@@ -2432,6 +2455,7 @@ set_control_mode()
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
}
+
break;
default:
@@ -2470,7 +2494,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
- tune_positive(true);
+ tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 7be8de9c6..53013fdb9 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -65,6 +65,7 @@ static const char *sensor_name = "mag";
int do_mag_calibration(int mavlink_fd)
{
+ int32_t device_id;
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
mavlink_log_info(mavlink_fd, "don't move system");
@@ -88,6 +89,9 @@ int do_mag_calibration(int mavlink_fd)
/* erase old calibration */
int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ device_id = ioctl(fd, DEVIOCGDEVICEID, 0);
+
res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
if (res != OK) {
@@ -146,54 +150,60 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
int sub_mag = orb_subscribe(ORB_ID(sensor_mag0));
- struct mag_report mag;
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
+ if (sub_mag < 0) {
+ mavlink_log_critical(mavlink_fd, "No mag found, abort");
+ res = ERROR;
+ } else {
+ struct mag_report mag;
+
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
+
+ /* calibrate offsets */
+ uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+ unsigned poll_errcount = 0;
- /* calibrate offsets */
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
- unsigned poll_errcount = 0;
+ mavlink_log_info(mavlink_fd, "Turn on all sides: front/back,left/right,up/down");
- mavlink_log_info(mavlink_fd, "Turn on all sides: front/back,left/right,up/down");
+ calibration_counter = 0U;
- calibration_counter = 0;
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_mag;
+ fds[0].events = POLLIN;
- /* wait blocking for new data */
- struct pollfd fds[1];
- fds[0].fd = sub_mag;
- fds[0].events = POLLIN;
+ int poll_ret = poll(fds, 1, 1000);
- int poll_ret = poll(fds, 1, 1000);
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_mag0), sub_mag, &mag);
- if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_mag0), sub_mag, &mag);
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
+ calibration_counter++;
- calibration_counter++;
+ if (calibration_counter % (calibration_maxcount / 20) == 0) {
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ }
- if (calibration_counter % (calibration_maxcount / 20) == 0) {
- mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ } else {
+ poll_errcount++;
}
- } else {
- poll_errcount++;
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
}
- if (poll_errcount > 1000) {
- mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
- res = ERROR;
- break;
- }
+ close(sub_mag);
}
-
- close(sub_mag);
}
float sphere_x;
@@ -201,7 +211,7 @@ int do_mag_calibration(int mavlink_fd)
float sphere_z;
float sphere_radius;
- if (res == OK) {
+ if (res == OK && calibration_counter > (calibration_maxcount / 2)) {
/* sphere fit */
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
@@ -253,6 +263,9 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
/* set parameters */
+ if (param_set(param_find("SENS_MAG_ID"), &(device_id))) {
+ res = ERROR;
+ }
if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
res = ERROR;
}
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 705e54be3..68bf12024 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -793,7 +793,7 @@ start(void)
sem_init(&g_init_sema, 1, 0);
/* start the worker thread */
- if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 2000, task_main, NULL)) <= 0) {
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 1800, task_main, NULL)) <= 0) {
warn("task start failed");
return -1;
}
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index 968270847..d51075b8c 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013-2015 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
@@ -82,12 +82,11 @@
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <mathlib/mathlib.h>
+#include <mathlib/math/filter/LowPassFilter2p.hpp>
#include <mavlink/mavlink_log.h>
#include <platforms/px4_defines.h>
-#include "estimator_23states.h"
-
-
+#include "estimator_22states.h"
/**
* estimator app start / stop handling function
@@ -102,7 +101,7 @@ __EXPORT uint64_t getMicros();
static uint64_t IMUmsec = 0;
static uint64_t IMUusec = 0;
-static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000;
+static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000; // units: microseconds
uint32_t millis()
{
@@ -223,8 +222,10 @@ private:
float _baro_ref; /**< barometer reference altitude */
float _baro_ref_offset; /**< offset between initial baro reference and GPS init baro altitude */
float _baro_gps_offset; /**< offset between baro altitude (at GPS init time) and GPS altitude */
+ hrt_abstime _last_debug_print = 0;
perf_counter_t _loop_perf; ///< loop performance counter
+ perf_counter_t _loop_intvl; ///< loop rate counter
perf_counter_t _perf_gyro; ///<local performance counter for gyro updates
perf_counter_t _perf_mag; ///<local performance counter for mag updates
perf_counter_t _perf_gps; ///<local performance counter for gps updates
@@ -291,10 +292,6 @@ private:
AttPosEKF *_ekf;
- float _velocity_xy_filtered;
- float _velocity_z_filtered;
- float _airspeed_filtered;
-
/**
* Update our local parameter cache.
*/
@@ -400,6 +397,7 @@ FixedwingEstimator::FixedwingEstimator() :
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "ekf_att_pos_estimator")),
+ _loop_intvl(perf_alloc(PC_INTERVAL, "ekf_att_pos_est_interval")),
_perf_gyro(perf_alloc(PC_INTERVAL, "ekf_att_pos_gyro_upd")),
_perf_mag(perf_alloc(PC_INTERVAL, "ekf_att_pos_mag_upd")),
_perf_gps(perf_alloc(PC_INTERVAL, "ekf_att_pos_gps_upd")),
@@ -423,10 +421,7 @@ FixedwingEstimator::FixedwingEstimator() :
_mavlink_fd(-1),
_parameters{},
_parameter_handles{},
- _ekf(nullptr),
- _velocity_xy_filtered(0.0f),
- _velocity_z_filtered(0.0f),
- _airspeed_filtered(0.0f)
+ _ekf(nullptr)
{
_last_run = hrt_absolute_time();
@@ -783,6 +778,11 @@ FixedwingEstimator::task_main()
_gps.vel_e_m_s = 0.0f;
_gps.vel_d_m_s = 0.0f;
+ // init lowpass filters for baro and gps altitude
+ float _gps_alt_filt = 0, _baro_alt_filt = 0;
+ float rc = 10.0f; // RC time constant of 1st order LPF in seconds
+ hrt_abstime baro_last = 0;
+
_task_running = true;
while (!_task_should_exit) {
@@ -801,6 +801,7 @@ FixedwingEstimator::task_main()
}
perf_begin(_loop_perf);
+ perf_count(_loop_intvl);
/* only update parameters if they changed */
if (fds[0].revents & POLLIN) {
@@ -1056,6 +1057,11 @@ FixedwingEstimator::task_main()
_ekf->gpsLon = math::radians(_gps.lon / (double)1e7) - M_PI;
_ekf->gpsHgt = _gps.alt / 1e3f;
+ // update LPF
+ _gps_alt_filt += (gps_elapsed / (rc + gps_elapsed)) * (_ekf->gpsHgt - _gps_alt_filt);
+
+ //warnx("gps alt: %6.1f, interval: %6.3f", (double)_ekf->gpsHgt, (double)gps_elapsed);
+
// if (_gps.s_variance_m_s > 0.25f && _gps.s_variance_m_s < 100.0f * 100.0f) {
// _ekf->vneSigma = sqrtf(_gps.s_variance_m_s);
// } else {
@@ -1071,7 +1077,6 @@ FixedwingEstimator::task_main()
// warnx("vel: %8.4f pos: %8.4f", _gps.s_variance_m_s, _gps.p_variance_m);
newDataGps = true;
-
last_gps = _gps.timestamp_position;
}
@@ -1083,15 +1088,15 @@ FixedwingEstimator::task_main()
if (baro_updated) {
- hrt_abstime baro_last = _baro.timestamp;
-
orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
float baro_elapsed = (_baro.timestamp - baro_last) / 1e6f;
+ baro_last = _baro.timestamp;
_ekf->updateDtHgtFilt(math::constrain(baro_elapsed, 0.001f, 0.1f));
_ekf->baroHgt = _baro.altitude;
+ _baro_alt_filt += (baro_elapsed/(rc + baro_elapsed)) * (_baro.altitude - _baro_alt_filt);
if (!_baro_init) {
_baro_ref = _baro.altitude;
@@ -1181,6 +1186,24 @@ FixedwingEstimator::task_main()
float initVelNED[3];
+ // maintain filtered baro and gps altitudes to calculate weather offset
+ // baro sample rate is ~70Hz and measurement bandwidth is high
+ // gps sample rate is 5Hz and altitude is assumed accurate when averaged over 30 seconds
+ // maintain heavily filtered values for both baro and gps altitude
+ // Assume the filtered output should be identical for both sensors
+ _baro_gps_offset = _baro_alt_filt - _gps_alt_filt;
+// if (hrt_elapsed_time(&_last_debug_print) >= 5e6) {
+// _last_debug_print = hrt_absolute_time();
+// perf_print_counter(_perf_baro);
+// perf_reset(_perf_baro);
+// warnx("gpsoff: %5.1f, baro_alt_filt: %6.1f, gps_alt_filt: %6.1f, gpos.alt: %5.1f, lpos.z: %6.1f",
+// (double)_baro_gps_offset,
+// (double)_baro_alt_filt,
+// (double)_gps_alt_filt,
+// (double)_global_pos.alt,
+// (double)_local_pos.z);
+// }
+
/* Initialize the filter first */
if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) {
@@ -1196,7 +1219,11 @@ FixedwingEstimator::task_main()
// Set up height correctly
orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
_baro_ref_offset = _ekf->states[9]; // this should become zero in the local frame
- _baro_gps_offset = _baro.altitude - gps_alt;
+
+ // init filtered gps and baro altitudes
+ _gps_alt_filt = gps_alt;
+ _baro_alt_filt = _baro.altitude;
+
_ekf->baroHgt = _baro.altitude;
_ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref));
@@ -1372,10 +1399,15 @@ FixedwingEstimator::task_main()
}
if (newRangeData) {
- _ekf->fuseRngData = true;
- _ekf->useRangeFinder = true;
- _ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 100.0f));
- _ekf->GroundEKF();
+
+ if (_ekf->Tnb.z.z > 0.9f) {
+ // _ekf->rngMea is set in sensor readout already
+ _ekf->fuseRngData = true;
+ _ekf->fuseOptFlowData = false;
+ _ekf->RecallStates(_ekf->statesAtRngTime, (IMUmsec - 100.0f));
+ _ekf->OpticalFlowEKF();
+ _ekf->fuseRngData = false;
+ }
}
@@ -1435,22 +1467,6 @@ FixedwingEstimator::task_main()
_local_pos.v_z_valid = true;
_local_pos.xy_global = true;
- _velocity_xy_filtered = 0.95f*_velocity_xy_filtered + 0.05f*sqrtf(_local_pos.vx*_local_pos.vx + _local_pos.vy*_local_pos.vy);
- _velocity_z_filtered = 0.95f*_velocity_z_filtered + 0.05f*fabsf(_local_pos.vz);
- _airspeed_filtered = 0.95f*_airspeed_filtered + 0.05f*_airspeed.true_airspeed_m_s;
-
-
- /* crude land detector for fixedwing only,
- * TODO: adapt so that it works for both, maybe move to another location
- */
- if (_velocity_xy_filtered < 5
- && _velocity_z_filtered < 10
- && _airspeed_filtered < 10) {
- _local_pos.landed = true;
- } else {
- _local_pos.landed = false;
- }
-
_local_pos.z_global = false;
_local_pos.yaw = _att.yaw;
@@ -1515,8 +1531,8 @@ FixedwingEstimator::task_main()
if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
_wind.timestamp = _global_pos.timestamp;
- _wind.windspeed_north = _ekf->windSpdFiltNorth;
- _wind.windspeed_east = _ekf->windSpdFiltEast;
+ _wind.windspeed_north = _ekf->states[14];
+ _wind.windspeed_east = _ekf->states[15];
// XXX we need to do something smart about the covariance here
// but we default to the estimate covariance for now
_wind.covariance_north = _ekf->P[14][14];
diff --git a/src/modules/ekf_att_pos_estimator/estimator_21states.cpp b/src/modules/ekf_att_pos_estimator/estimator_21states.cpp
deleted file mode 100644
index 67bfec4ea..000000000
--- a/src/modules/ekf_att_pos_estimator/estimator_21states.cpp
+++ /dev/null
@@ -1,2142 +0,0 @@
-#include "estimator_21states.h"
-
-#include <string.h>
-
-AttPosEKF::AttPosEKF() :
- fusionModeGPS(0),
- covSkipCount(0),
- EAS2TAS(1.0f),
- statesInitialised(false),
- fuseVelData(false),
- fusePosData(false),
- fuseHgtData(false),
- fuseMagData(false),
- fuseVtasData(false),
- onGround(true),
- staticMode(true),
- useAirspeed(true),
- useCompass(true),
- numericalProtection(true),
- storeIndex(0),
- magDeclination(0.0f)
-{
- InitialiseParameters();
-}
-
-AttPosEKF::~AttPosEKF()
-{
-}
-
-void AttPosEKF::UpdateStrapdownEquationsNED()
-{
- Vector3f delVelNav;
- float q00;
- float q11;
- float q22;
- float q33;
- float q01;
- float q02;
- float q03;
- float q12;
- float q13;
- float q23;
- Mat3f Tbn;
- Mat3f Tnb;
- float rotationMag;
- float qUpdated[4];
- float quatMag;
- double deltaQuat[4];
- const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS};
-
-// Remove sensor bias errors
- correctedDelAng.x = dAngIMU.x - states[10];
- correctedDelAng.y = dAngIMU.y - states[11];
- correctedDelAng.z = dAngIMU.z - states[12];
- dVelIMU.x = dVelIMU.x;
- dVelIMU.y = dVelIMU.y;
- dVelIMU.z = dVelIMU.z;
-
-// Save current measurements
- Vector3f prevDelAng = correctedDelAng;
-
-// Apply corrections for earths rotation rate and coning errors
-// * and + operators have been overloaded
- correctedDelAng = correctedDelAng - Tnb*earthRateNED*dtIMU + 8.333333333333333e-2f*(prevDelAng % correctedDelAng);
-// Convert the rotation vector to its equivalent quaternion
- rotationMag = correctedDelAng.length();
- if (rotationMag < 1e-12f)
- {
- deltaQuat[0] = 1.0;
- deltaQuat[1] = 0.0;
- deltaQuat[2] = 0.0;
- deltaQuat[3] = 0.0;
- }
- else
- {
- deltaQuat[0] = cos(0.5f*rotationMag);
- double rotScaler = (sin(0.5f*rotationMag))/rotationMag;
- deltaQuat[1] = correctedDelAng.x*rotScaler;
- deltaQuat[2] = correctedDelAng.y*rotScaler;
- deltaQuat[3] = correctedDelAng.z*rotScaler;
- }
-
-// Update the quaternions by rotating from the previous attitude through
-// the delta angle rotation quaternion
- qUpdated[0] = states[0]*deltaQuat[0] - states[1]*deltaQuat[1] - states[2]*deltaQuat[2] - states[3]*deltaQuat[3];
- qUpdated[1] = states[0]*deltaQuat[1] + states[1]*deltaQuat[0] + states[2]*deltaQuat[3] - states[3]*deltaQuat[2];
- qUpdated[2] = states[0]*deltaQuat[2] + states[2]*deltaQuat[0] + states[3]*deltaQuat[1] - states[1]*deltaQuat[3];
- qUpdated[3] = states[0]*deltaQuat[3] + states[3]*deltaQuat[0] + states[1]*deltaQuat[2] - states[2]*deltaQuat[1];
-
-// Normalise the quaternions and update the quaternion states
- quatMag = sqrtf(sq(qUpdated[0]) + sq(qUpdated[1]) + sq(qUpdated[2]) + sq(qUpdated[3]));
- if (quatMag > 1e-16f)
- {
- float quatMagInv = 1.0f/quatMag;
- states[0] = quatMagInv*qUpdated[0];
- states[1] = quatMagInv*qUpdated[1];
- states[2] = quatMagInv*qUpdated[2];
- states[3] = quatMagInv*qUpdated[3];
- }
-
-// Calculate the body to nav cosine matrix
- q00 = sq(states[0]);
- q11 = sq(states[1]);
- q22 = sq(states[2]);
- q33 = sq(states[3]);
- q01 = states[0]*states[1];
- q02 = states[0]*states[2];
- q03 = states[0]*states[3];
- q12 = states[1]*states[2];
- q13 = states[1]*states[3];
- q23 = states[2]*states[3];
-
- Tbn.x.x = q00 + q11 - q22 - q33;
- Tbn.y.y = q00 - q11 + q22 - q33;
- Tbn.z.z = q00 - q11 - q22 + q33;
- Tbn.x.y = 2*(q12 - q03);
- Tbn.x.z = 2*(q13 + q02);
- Tbn.y.x = 2*(q12 + q03);
- Tbn.y.z = 2*(q23 - q01);
- Tbn.z.x = 2*(q13 - q02);
- Tbn.z.y = 2*(q23 + q01);
-
- Tnb = Tbn.transpose();
-
-// transform body delta velocities to delta velocities in the nav frame
-// * and + operators have been overloaded
- //delVelNav = Tbn*dVelIMU + gravityNED*dtIMU;
- delVelNav.x = Tbn.x.x*dVelIMU.x + Tbn.x.y*dVelIMU.y + Tbn.x.z*dVelIMU.z + gravityNED.x*dtIMU;
- delVelNav.y = Tbn.y.x*dVelIMU.x + Tbn.y.y*dVelIMU.y + Tbn.y.z*dVelIMU.z + gravityNED.y*dtIMU;
- delVelNav.z = Tbn.z.x*dVelIMU.x + Tbn.z.y*dVelIMU.y + Tbn.z.z*dVelIMU.z + gravityNED.z*dtIMU;
-
-// calculate the magnitude of the nav acceleration (required for GPS
-// variance estimation)
- accNavMag = delVelNav.length()/dtIMU;
-
-// If calculating position save previous velocity
- float lastVelocity[3];
- lastVelocity[0] = states[4];
- lastVelocity[1] = states[5];
- lastVelocity[2] = states[6];
-
-// Sum delta velocities to get velocity
- states[4] = states[4] + delVelNav.x;
- states[5] = states[5] + delVelNav.y;
- states[6] = states[6] + delVelNav.z;
-
-// If calculating postions, do a trapezoidal integration for position
- states[7] = states[7] + 0.5f*(states[4] + lastVelocity[0])*dtIMU;
- states[8] = states[8] + 0.5f*(states[5] + lastVelocity[1])*dtIMU;
- states[9] = states[9] + 0.5f*(states[6] + lastVelocity[2])*dtIMU;
-
- // Constrain states (to protect against filter divergence)
- //ConstrainStates();
-}
-
-void AttPosEKF::CovariancePrediction(float dt)
-{
- // scalars
- float daxCov;
- float dayCov;
- float dazCov;
- float dvxCov;
- float dvyCov;
- float dvzCov;
- float dvx;
- float dvy;
- float dvz;
- float dax;
- float day;
- float daz;
- float q0;
- float q1;
- float q2;
- float q3;
- float dax_b;
- float day_b;
- float daz_b;
-
- // arrays
- float processNoise[21];
- float SF[14];
- float SG[8];
- float SQ[11];
- float SPP[13] = {0};
- float nextP[21][21];
-
- // calculate covariance prediction process noise
- windVelSigma = dt*0.1f;
- dAngBiasSigma = dt*5.0e-7f;
- magEarthSigma = dt*3.0e-4f;
- magBodySigma = dt*3.0e-4f;
- for (uint8_t i= 0; i<=9; i++) processNoise[i] = 1.0e-9f;
- for (uint8_t i=10; i<=12; i++) processNoise[i] = dAngBiasSigma;
- if (onGround) processNoise[12] = dAngBiasSigma * yawVarScale;
- for (uint8_t i=13; i<=14; i++) processNoise[i] = windVelSigma;
- for (uint8_t i=15; i<=17; i++) processNoise[i] = magEarthSigma;
- for (uint8_t i=18; i<=20; i++) processNoise[i] = magBodySigma;
- for (uint8_t i= 0; i<=20; i++) processNoise[i] = sq(processNoise[i]);
-
- // set variables used to calculate covariance growth
- dvx = summedDelVel.x;
- dvy = summedDelVel.y;
- dvz = summedDelVel.z;
- dax = summedDelAng.x;
- day = summedDelAng.y;
- daz = summedDelAng.z;
- q0 = states[0];
- q1 = states[1];
- q2 = states[2];
- q3 = states[3];
- dax_b = states[10];
- day_b = states[11];
- daz_b = states[12];
- daxCov = sq(dt*1.4544411e-2f);
- dayCov = sq(dt*1.4544411e-2f);
- dazCov = sq(dt*1.4544411e-2f);
- if (onGround) dazCov = dazCov * sq(yawVarScale);
- dvxCov = sq(dt*0.5f);
- dvyCov = sq(dt*0.5f);
- dvzCov = sq(dt*0.5f);
-
- // Predicted covariance calculation
- SF[0] = 2*dvx*q1 + 2*dvy*q2 + 2*dvz*q3;
- SF[1] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
- SF[2] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
- SF[3] = day/2 - day_b/2;
- SF[4] = daz/2 - daz_b/2;
- SF[5] = dax/2 - dax_b/2;
- SF[6] = dax_b/2 - dax/2;
- SF[7] = daz_b/2 - daz/2;
- SF[8] = day_b/2 - day/2;
- SF[9] = q1/2;
- SF[10] = q2/2;
- SF[11] = q3/2;
- SF[12] = 2*dvz*q0;
- SF[13] = 2*dvy*q1;
-
- SG[0] = q0/2;
- SG[1] = sq(q3);
- SG[2] = sq(q2);
- SG[3] = sq(q1);
- SG[4] = sq(q0);
- SG[5] = 2*q2*q3;
- SG[6] = 2*q1*q3;
- SG[7] = 2*q1*q2;
-
- SQ[0] = dvzCov*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyCov*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxCov*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3);
- SQ[1] = dvzCov*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxCov*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyCov*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3);
- SQ[2] = dvzCov*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyCov*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxCov*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]);
- SQ[3] = (dayCov*q1*SG[0])/2 - (dazCov*q1*SG[0])/2 - (daxCov*q2*q3)/4;
- SQ[4] = (dazCov*q2*SG[0])/2 - (daxCov*q2*SG[0])/2 - (dayCov*q1*q3)/4;
- SQ[5] = (daxCov*q3*SG[0])/2 - (dayCov*q3*SG[0])/2 - (dazCov*q1*q2)/4;
- SQ[6] = (daxCov*q1*q2)/4 - (dazCov*q3*SG[0])/2 - (dayCov*q1*q2)/4;
- SQ[7] = (dazCov*q1*q3)/4 - (daxCov*q1*q3)/4 - (dayCov*q2*SG[0])/2;
- SQ[8] = (dayCov*q2*q3)/4 - (daxCov*q1*SG[0])/2 - (dazCov*q2*q3)/4;
- SQ[9] = sq(SG[0]);
- SQ[10] = sq(q1);
-
- SPP[0] = SF[12] + SF[13] - 2*dvx*q2;
- SPP[1] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
- SPP[2] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
- SPP[3] = SF[11];
- SPP[4] = SF[10];
- SPP[5] = SF[9];
- SPP[6] = SF[7];
- SPP[7] = SF[8];
-
- nextP[0][0] = P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3] + (daxCov*SQ[10])/4 + SF[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[7]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[6]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[5]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[4]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) + SPP[3]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) + (dayCov*sq(q2))/4 + (dazCov*sq(q3))/4;
- nextP[0][1] = P[0][1] + SQ[8] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3] + SF[5]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[4]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[7]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[3]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - SPP[4]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]))/2;
- nextP[0][2] = P[0][2] + SQ[7] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3] + SF[3]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[5]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) - SPP[3]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[5]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]))/2;
- nextP[0][3] = P[0][3] + SQ[6] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3] + SF[4]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[3]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[6]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[4]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) - SPP[5]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - (q0*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]))/2;
- nextP[0][4] = P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3] + SF[2]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) - SPP[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]);
- nextP[0][5] = P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3] + SF[1]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SF[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) - SPP[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]);
- nextP[0][6] = P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3] + SF[1]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[0]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[0]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) - SPP[1]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]);
- nextP[0][7] = P[0][7] + P[1][7]*SF[6] + P[2][7]*SPP[7] + P[3][7]*SPP[6] + P[10][7]*SPP[5] + P[11][7]*SPP[4] + P[12][7]*SPP[3] + dt*(P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3]);
- nextP[0][8] = P[0][8] + P[1][8]*SF[6] + P[2][8]*SPP[7] + P[3][8]*SPP[6] + P[10][8]*SPP[5] + P[11][8]*SPP[4] + P[12][8]*SPP[3] + dt*(P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3]);
- nextP[0][9] = P[0][9] + P[1][9]*SF[6] + P[2][9]*SPP[7] + P[3][9]*SPP[6] + P[10][9]*SPP[5] + P[11][9]*SPP[4] + P[12][9]*SPP[3] + dt*(P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3]);
- nextP[0][10] = P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3];
- nextP[0][11] = P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3];
- nextP[0][12] = P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3];
- nextP[0][13] = P[0][13] + P[1][13]*SF[6] + P[2][13]*SPP[7] + P[3][13]*SPP[6] + P[10][13]*SPP[5] + P[11][13]*SPP[4] + P[12][13]*SPP[3];
- nextP[0][14] = P[0][14] + P[1][14]*SF[6] + P[2][14]*SPP[7] + P[3][14]*SPP[6] + P[10][14]*SPP[5] + P[11][14]*SPP[4] + P[12][14]*SPP[3];
- nextP[0][15] = P[0][15] + P[1][15]*SF[6] + P[2][15]*SPP[7] + P[3][15]*SPP[6] + P[10][15]*SPP[5] + P[11][15]*SPP[4] + P[12][15]*SPP[3];
- nextP[0][16] = P[0][16] + P[1][16]*SF[6] + P[2][16]*SPP[7] + P[3][16]*SPP[6] + P[10][16]*SPP[5] + P[11][16]*SPP[4] + P[12][16]*SPP[3];
- nextP[0][17] = P[0][17] + P[1][17]*SF[6] + P[2][17]*SPP[7] + P[3][17]*SPP[6] + P[10][17]*SPP[5] + P[11][17]*SPP[4] + P[12][17]*SPP[3];
- nextP[0][18] = P[0][18] + P[1][18]*SF[6] + P[2][18]*SPP[7] + P[3][18]*SPP[6] + P[10][18]*SPP[5] + P[11][18]*SPP[4] + P[12][18]*SPP[3];
- nextP[0][19] = P[0][19] + P[1][19]*SF[6] + P[2][19]*SPP[7] + P[3][19]*SPP[6] + P[10][19]*SPP[5] + P[11][19]*SPP[4] + P[12][19]*SPP[3];
- nextP[0][20] = P[0][20] + P[1][20]*SF[6] + P[2][20]*SPP[7] + P[3][20]*SPP[6] + P[10][20]*SPP[5] + P[11][20]*SPP[4] + P[12][20]*SPP[3];
- nextP[1][0] = P[1][0] + SQ[8] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2 + SF[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[7]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[6]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[5]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[4]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) + SPP[3]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2);
- nextP[1][1] = P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] + daxCov*SQ[9] - (P[10][1]*q0)/2 + SF[5]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[4]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[7]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[3]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - SPP[4]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) + (dayCov*sq(q3))/4 + (dazCov*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2))/2;
- nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2 + SF[3]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[5]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) - SPP[3]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[5]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2))/2;
- nextP[1][3] = P[1][3] + SQ[4] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[3]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[6]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[4]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) - SPP[5]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - (q0*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2))/2;
- nextP[1][4] = P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2 + SF[2]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) - SPP[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2);
- nextP[1][5] = P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2 + SF[1]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SF[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) - SPP[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2);
- nextP[1][6] = P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2 + SF[1]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[0]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[0]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) - SPP[1]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2);
- nextP[1][7] = P[1][7] + P[0][7]*SF[5] + P[2][7]*SF[4] + P[3][7]*SPP[7] + P[11][7]*SPP[3] - P[12][7]*SPP[4] - (P[10][7]*q0)/2 + dt*(P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2);
- nextP[1][8] = P[1][8] + P[0][8]*SF[5] + P[2][8]*SF[4] + P[3][8]*SPP[7] + P[11][8]*SPP[3] - P[12][8]*SPP[4] - (P[10][8]*q0)/2 + dt*(P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2);
- nextP[1][9] = P[1][9] + P[0][9]*SF[5] + P[2][9]*SF[4] + P[3][9]*SPP[7] + P[11][9]*SPP[3] - P[12][9]*SPP[4] - (P[10][9]*q0)/2 + dt*(P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2);
- nextP[1][10] = P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2;
- nextP[1][11] = P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2;
- nextP[1][12] = P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2;
- nextP[1][13] = P[1][13] + P[0][13]*SF[5] + P[2][13]*SF[4] + P[3][13]*SPP[7] + P[11][13]*SPP[3] - P[12][13]*SPP[4] - (P[10][13]*q0)/2;
- nextP[1][14] = P[1][14] + P[0][14]*SF[5] + P[2][14]*SF[4] + P[3][14]*SPP[7] + P[11][14]*SPP[3] - P[12][14]*SPP[4] - (P[10][14]*q0)/2;
- nextP[1][15] = P[1][15] + P[0][15]*SF[5] + P[2][15]*SF[4] + P[3][15]*SPP[7] + P[11][15]*SPP[3] - P[12][15]*SPP[4] - (P[10][15]*q0)/2;
- nextP[1][16] = P[1][16] + P[0][16]*SF[5] + P[2][16]*SF[4] + P[3][16]*SPP[7] + P[11][16]*SPP[3] - P[12][16]*SPP[4] - (P[10][16]*q0)/2;
- nextP[1][17] = P[1][17] + P[0][17]*SF[5] + P[2][17]*SF[4] + P[3][17]*SPP[7] + P[11][17]*SPP[3] - P[12][17]*SPP[4] - (P[10][17]*q0)/2;
- nextP[1][18] = P[1][18] + P[0][18]*SF[5] + P[2][18]*SF[4] + P[3][18]*SPP[7] + P[11][18]*SPP[3] - P[12][18]*SPP[4] - (P[10][18]*q0)/2;
- nextP[1][19] = P[1][19] + P[0][19]*SF[5] + P[2][19]*SF[4] + P[3][19]*SPP[7] + P[11][19]*SPP[3] - P[12][19]*SPP[4] - (P[10][19]*q0)/2;
- nextP[1][20] = P[1][20] + P[0][20]*SF[5] + P[2][20]*SF[4] + P[3][20]*SPP[7] + P[11][20]*SPP[3] - P[12][20]*SPP[4] - (P[10][20]*q0)/2;
- nextP[2][0] = P[2][0] + SQ[7] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2 + SF[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[7]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[6]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[5]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[4]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) + SPP[3]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2);
- nextP[2][1] = P[2][1] + SQ[5] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2 + SF[5]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[4]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[7]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[3]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - SPP[4]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) - (q0*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2))/2;
- nextP[2][2] = P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] + dayCov*SQ[9] + (dazCov*SQ[10])/4 - (P[11][2]*q0)/2 + SF[3]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[5]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) - SPP[3]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[5]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) + (daxCov*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2))/2;
- nextP[2][3] = P[2][3] + SQ[3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[3]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[6]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[4]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) - SPP[5]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - (q0*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2))/2;
- nextP[2][4] = P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2 + SF[2]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) - SPP[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2);
- nextP[2][5] = P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2 + SF[1]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SF[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) - SPP[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2);
- nextP[2][6] = P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2 + SF[1]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[0]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[0]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) - SPP[1]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2);
- nextP[2][7] = P[2][7] + P[0][7]*SF[3] + P[3][7]*SF[5] + P[1][7]*SPP[6] - P[10][7]*SPP[3] + P[12][7]*SPP[5] - (P[11][7]*q0)/2 + dt*(P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2);
- nextP[2][8] = P[2][8] + P[0][8]*SF[3] + P[3][8]*SF[5] + P[1][8]*SPP[6] - P[10][8]*SPP[3] + P[12][8]*SPP[5] - (P[11][8]*q0)/2 + dt*(P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2);
- nextP[2][9] = P[2][9] + P[0][9]*SF[3] + P[3][9]*SF[5] + P[1][9]*SPP[6] - P[10][9]*SPP[3] + P[12][9]*SPP[5] - (P[11][9]*q0)/2 + dt*(P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2);
- nextP[2][10] = P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2;
- nextP[2][11] = P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2;
- nextP[2][12] = P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2;
- nextP[2][13] = P[2][13] + P[0][13]*SF[3] + P[3][13]*SF[5] + P[1][13]*SPP[6] - P[10][13]*SPP[3] + P[12][13]*SPP[5] - (P[11][13]*q0)/2;
- nextP[2][14] = P[2][14] + P[0][14]*SF[3] + P[3][14]*SF[5] + P[1][14]*SPP[6] - P[10][14]*SPP[3] + P[12][14]*SPP[5] - (P[11][14]*q0)/2;
- nextP[2][15] = P[2][15] + P[0][15]*SF[3] + P[3][15]*SF[5] + P[1][15]*SPP[6] - P[10][15]*SPP[3] + P[12][15]*SPP[5] - (P[11][15]*q0)/2;
- nextP[2][16] = P[2][16] + P[0][16]*SF[3] + P[3][16]*SF[5] + P[1][16]*SPP[6] - P[10][16]*SPP[3] + P[12][16]*SPP[5] - (P[11][16]*q0)/2;
- nextP[2][17] = P[2][17] + P[0][17]*SF[3] + P[3][17]*SF[5] + P[1][17]*SPP[6] - P[10][17]*SPP[3] + P[12][17]*SPP[5] - (P[11][17]*q0)/2;
- nextP[2][18] = P[2][18] + P[0][18]*SF[3] + P[3][18]*SF[5] + P[1][18]*SPP[6] - P[10][18]*SPP[3] + P[12][18]*SPP[5] - (P[11][18]*q0)/2;
- nextP[2][19] = P[2][19] + P[0][19]*SF[3] + P[3][19]*SF[5] + P[1][19]*SPP[6] - P[10][19]*SPP[3] + P[12][19]*SPP[5] - (P[11][19]*q0)/2;
- nextP[2][20] = P[2][20] + P[0][20]*SF[3] + P[3][20]*SF[5] + P[1][20]*SPP[6] - P[10][20]*SPP[3] + P[12][20]*SPP[5] - (P[11][20]*q0)/2;
- nextP[3][0] = P[3][0] + SQ[6] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2 + SF[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[7]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[6]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[5]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[4]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + SPP[3]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2);
- nextP[3][1] = P[3][1] + SQ[4] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2 + SF[5]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[4]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[7]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[3]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) - SPP[4]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2))/2;
- nextP[3][2] = P[3][2] + SQ[3] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2 + SF[3]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[5]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) - SPP[3]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[5]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2))/2;
- nextP[3][3] = P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] + (dayCov*SQ[10])/4 + dazCov*SQ[9] - (P[12][3]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[3]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[6]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[4]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) - SPP[5]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + (daxCov*sq(q2))/4 - (q0*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2))/2;
- nextP[3][4] = P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2 + SF[2]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) - SPP[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2);
- nextP[3][5] = P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2 + SF[1]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SF[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) - SPP[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2);
- nextP[3][6] = P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2 + SF[1]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[0]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[0]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) - SPP[1]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2);
- nextP[3][7] = P[3][7] + P[0][7]*SF[4] + P[1][7]*SF[3] + P[2][7]*SF[6] + P[10][7]*SPP[4] - P[11][7]*SPP[5] - (P[12][7]*q0)/2 + dt*(P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2);
- nextP[3][8] = P[3][8] + P[0][8]*SF[4] + P[1][8]*SF[3] + P[2][8]*SF[6] + P[10][8]*SPP[4] - P[11][8]*SPP[5] - (P[12][8]*q0)/2 + dt*(P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2);
- nextP[3][9] = P[3][9] + P[0][9]*SF[4] + P[1][9]*SF[3] + P[2][9]*SF[6] + P[10][9]*SPP[4] - P[11][9]*SPP[5] - (P[12][9]*q0)/2 + dt*(P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2);
- nextP[3][10] = P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2;
- nextP[3][11] = P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2;
- nextP[3][12] = P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2;
- nextP[3][13] = P[3][13] + P[0][13]*SF[4] + P[1][13]*SF[3] + P[2][13]*SF[6] + P[10][13]*SPP[4] - P[11][13]*SPP[5] - (P[12][13]*q0)/2;
- nextP[3][14] = P[3][14] + P[0][14]*SF[4] + P[1][14]*SF[3] + P[2][14]*SF[6] + P[10][14]*SPP[4] - P[11][14]*SPP[5] - (P[12][14]*q0)/2;
- nextP[3][15] = P[3][15] + P[0][15]*SF[4] + P[1][15]*SF[3] + P[2][15]*SF[6] + P[10][15]*SPP[4] - P[11][15]*SPP[5] - (P[12][15]*q0)/2;
- nextP[3][16] = P[3][16] + P[0][16]*SF[4] + P[1][16]*SF[3] + P[2][16]*SF[6] + P[10][16]*SPP[4] - P[11][16]*SPP[5] - (P[12][16]*q0)/2;
- nextP[3][17] = P[3][17] + P[0][17]*SF[4] + P[1][17]*SF[3] + P[2][17]*SF[6] + P[10][17]*SPP[4] - P[11][17]*SPP[5] - (P[12][17]*q0)/2;
- nextP[3][18] = P[3][18] + P[0][18]*SF[4] + P[1][18]*SF[3] + P[2][18]*SF[6] + P[10][18]*SPP[4] - P[11][18]*SPP[5] - (P[12][18]*q0)/2;
- nextP[3][19] = P[3][19] + P[0][19]*SF[4] + P[1][19]*SF[3] + P[2][19]*SF[6] + P[10][19]*SPP[4] - P[11][19]*SPP[5] - (P[12][19]*q0)/2;
- nextP[3][20] = P[3][20] + P[0][20]*SF[4] + P[1][20]*SF[3] + P[2][20]*SF[6] + P[10][20]*SPP[4] - P[11][20]*SPP[5] - (P[12][20]*q0)/2;
- nextP[4][0] = P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2] + SF[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[7]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[6]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[5]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[4]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) + SPP[3]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]);
- nextP[4][1] = P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2] + SF[5]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[4]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[7]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[3]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - SPP[4]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]))/2;
- nextP[4][2] = P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2] + SF[3]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[5]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) - SPP[3]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[5]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]))/2;
- nextP[4][3] = P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2] + SF[4]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[3]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[6]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[4]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) - SPP[5]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - (q0*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]))/2;
- nextP[4][4] = P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2] + dvyCov*sq(SG[7] - 2*q0*q3) + dvzCov*sq(SG[6] + 2*q0*q2) + SF[2]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) - SPP[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + dvxCov*sq(SG[1] + SG[2] - SG[3] - SG[4]);
- nextP[4][5] = P[4][5] + SQ[2] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2] + SF[1]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SF[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) - SPP[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]);
- nextP[4][6] = P[4][6] + SQ[1] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2] + SF[1]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[0]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[0]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) - SPP[1]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]);
- nextP[4][7] = P[4][7] + P[0][7]*SF[2] + P[1][7]*SF[0] + P[2][7]*SPP[0] - P[3][7]*SPP[2] + dt*(P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2]);
- nextP[4][8] = P[4][8] + P[0][8]*SF[2] + P[1][8]*SF[0] + P[2][8]*SPP[0] - P[3][8]*SPP[2] + dt*(P[4][5] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2]);
- nextP[4][9] = P[4][9] + P[0][9]*SF[2] + P[1][9]*SF[0] + P[2][9]*SPP[0] - P[3][9]*SPP[2] + dt*(P[4][6] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2]);
- nextP[4][10] = P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2];
- nextP[4][11] = P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2];
- nextP[4][12] = P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2];
- nextP[4][13] = P[4][13] + P[0][13]*SF[2] + P[1][13]*SF[0] + P[2][13]*SPP[0] - P[3][13]*SPP[2];
- nextP[4][14] = P[4][14] + P[0][14]*SF[2] + P[1][14]*SF[0] + P[2][14]*SPP[0] - P[3][14]*SPP[2];
- nextP[4][15] = P[4][15] + P[0][15]*SF[2] + P[1][15]*SF[0] + P[2][15]*SPP[0] - P[3][15]*SPP[2];
- nextP[4][16] = P[4][16] + P[0][16]*SF[2] + P[1][16]*SF[0] + P[2][16]*SPP[0] - P[3][16]*SPP[2];
- nextP[4][17] = P[4][17] + P[0][17]*SF[2] + P[1][17]*SF[0] + P[2][17]*SPP[0] - P[3][17]*SPP[2];
- nextP[4][18] = P[4][18] + P[0][18]*SF[2] + P[1][18]*SF[0] + P[2][18]*SPP[0] - P[3][18]*SPP[2];
- nextP[4][19] = P[4][19] + P[0][19]*SF[2] + P[1][19]*SF[0] + P[2][19]*SPP[0] - P[3][19]*SPP[2];
- nextP[4][20] = P[4][20] + P[0][20]*SF[2] + P[1][20]*SF[0] + P[2][20]*SPP[0] - P[3][20]*SPP[2];
- nextP[5][0] = P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0] + SF[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[7]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[6]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[5]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[4]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) + SPP[3]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]);
- nextP[5][1] = P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0] + SF[5]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[4]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[7]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[3]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - SPP[4]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]))/2;
- nextP[5][2] = P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0] + SF[3]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[5]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) - SPP[3]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[5]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]))/2;
- nextP[5][3] = P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0] + SF[4]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[3]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[6]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[4]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) - SPP[5]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - (q0*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]))/2;
- nextP[5][4] = P[5][4] + SQ[2] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0] + SF[2]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) - SPP[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]);
- nextP[5][5] = P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0] + dvxCov*sq(SG[7] + 2*q0*q3) + dvzCov*sq(SG[5] - 2*q0*q1) + SF[1]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SF[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) - SPP[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + dvyCov*sq(SG[1] - SG[2] + SG[3] - SG[4]);
- nextP[5][6] = P[5][6] + SQ[0] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0] + SF[1]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[0]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[0]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) - SPP[1]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]);
- nextP[5][7] = P[5][7] + P[0][7]*SF[1] + P[2][7]*SF[0] + P[3][7]*SF[2] - P[1][7]*SPP[0] + dt*(P[5][4] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0]);
- nextP[5][8] = P[5][8] + P[0][8]*SF[1] + P[2][8]*SF[0] + P[3][8]*SF[2] - P[1][8]*SPP[0] + dt*(P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0]);
- nextP[5][9] = P[5][9] + P[0][9]*SF[1] + P[2][9]*SF[0] + P[3][9]*SF[2] - P[1][9]*SPP[0] + dt*(P[5][6] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0]);
- nextP[5][10] = P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0];
- nextP[5][11] = P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0];
- nextP[5][12] = P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0];
- nextP[5][13] = P[5][13] + P[0][13]*SF[1] + P[2][13]*SF[0] + P[3][13]*SF[2] - P[1][13]*SPP[0];
- nextP[5][14] = P[5][14] + P[0][14]*SF[1] + P[2][14]*SF[0] + P[3][14]*SF[2] - P[1][14]*SPP[0];
- nextP[5][15] = P[5][15] + P[0][15]*SF[1] + P[2][15]*SF[0] + P[3][15]*SF[2] - P[1][15]*SPP[0];
- nextP[5][16] = P[5][16] + P[0][16]*SF[1] + P[2][16]*SF[0] + P[3][16]*SF[2] - P[1][16]*SPP[0];
- nextP[5][17] = P[5][17] + P[0][17]*SF[1] + P[2][17]*SF[0] + P[3][17]*SF[2] - P[1][17]*SPP[0];
- nextP[5][18] = P[5][18] + P[0][18]*SF[1] + P[2][18]*SF[0] + P[3][18]*SF[2] - P[1][18]*SPP[0];
- nextP[5][19] = P[5][19] + P[0][19]*SF[1] + P[2][19]*SF[0] + P[3][19]*SF[2] - P[1][19]*SPP[0];
- nextP[5][20] = P[5][20] + P[0][20]*SF[1] + P[2][20]*SF[0] + P[3][20]*SF[2] - P[1][20]*SPP[0];
- nextP[6][0] = P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1] + SF[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[7]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[6]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[5]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[4]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) + SPP[3]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]);
- nextP[6][1] = P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1] + SF[5]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[4]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[7]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[3]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - SPP[4]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]))/2;
- nextP[6][2] = P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1] + SF[3]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[5]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) - SPP[3]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[5]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]))/2;
- nextP[6][3] = P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1] + SF[4]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[3]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[6]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[4]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) - SPP[5]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - (q0*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]))/2;
- nextP[6][4] = P[6][4] + SQ[1] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1] + SF[2]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) - SPP[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]);
- nextP[6][5] = P[6][5] + SQ[0] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1] + SF[1]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SF[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) - SPP[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]);
- nextP[6][6] = P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1] + dvxCov*sq(SG[6] - 2*q0*q2) + dvyCov*sq(SG[5] + 2*q0*q1) + SF[1]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[0]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[0]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) - SPP[1]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + dvzCov*sq(SG[1] - SG[2] - SG[3] + SG[4]);
- nextP[6][7] = P[6][7] + P[1][7]*SF[1] + P[3][7]*SF[0] + P[0][7]*SPP[0] - P[2][7]*SPP[1] + dt*(P[6][4] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1]);
- nextP[6][8] = P[6][8] + P[1][8]*SF[1] + P[3][8]*SF[0] + P[0][8]*SPP[0] - P[2][8]*SPP[1] + dt*(P[6][5] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1]);
- nextP[6][9] = P[6][9] + P[1][9]*SF[1] + P[3][9]*SF[0] + P[0][9]*SPP[0] - P[2][9]*SPP[1] + dt*(P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1]);
- nextP[6][10] = P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1];
- nextP[6][11] = P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1];
- nextP[6][12] = P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1];
- nextP[6][13] = P[6][13] + P[1][13]*SF[1] + P[3][13]*SF[0] + P[0][13]*SPP[0] - P[2][13]*SPP[1];
- nextP[6][14] = P[6][14] + P[1][14]*SF[1] + P[3][14]*SF[0] + P[0][14]*SPP[0] - P[2][14]*SPP[1];
- nextP[6][15] = P[6][15] + P[1][15]*SF[1] + P[3][15]*SF[0] + P[0][15]*SPP[0] - P[2][15]*SPP[1];
- nextP[6][16] = P[6][16] + P[1][16]*SF[1] + P[3][16]*SF[0] + P[0][16]*SPP[0] - P[2][16]*SPP[1];
- nextP[6][17] = P[6][17] + P[1][17]*SF[1] + P[3][17]*SF[0] + P[0][17]*SPP[0] - P[2][17]*SPP[1];
- nextP[6][18] = P[6][18] + P[1][18]*SF[1] + P[3][18]*SF[0] + P[0][18]*SPP[0] - P[2][18]*SPP[1];
- nextP[6][19] = P[6][19] + P[1][19]*SF[1] + P[3][19]*SF[0] + P[0][19]*SPP[0] - P[2][19]*SPP[1];
- nextP[6][20] = P[6][20] + P[1][20]*SF[1] + P[3][20]*SF[0] + P[0][20]*SPP[0] - P[2][20]*SPP[1];
- nextP[7][0] = P[7][0] + P[4][0]*dt + SF[6]*(P[7][1] + P[4][1]*dt) + SPP[7]*(P[7][2] + P[4][2]*dt) + SPP[6]*(P[7][3] + P[4][3]*dt) + SPP[5]*(P[7][10] + P[4][10]*dt) + SPP[4]*(P[7][11] + P[4][11]*dt) + SPP[3]*(P[7][12] + P[4][12]*dt);
- nextP[7][1] = P[7][1] + P[4][1]*dt + SF[5]*(P[7][0] + P[4][0]*dt) + SF[4]*(P[7][2] + P[4][2]*dt) + SPP[7]*(P[7][3] + P[4][3]*dt) + SPP[3]*(P[7][11] + P[4][11]*dt) - SPP[4]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][10] + P[4][10]*dt))/2;
- nextP[7][2] = P[7][2] + P[4][2]*dt + SF[3]*(P[7][0] + P[4][0]*dt) + SF[5]*(P[7][3] + P[4][3]*dt) + SPP[6]*(P[7][1] + P[4][1]*dt) - SPP[3]*(P[7][10] + P[4][10]*dt) + SPP[5]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][11] + P[4][11]*dt))/2;
- nextP[7][3] = P[7][3] + P[4][3]*dt + SF[4]*(P[7][0] + P[4][0]*dt) + SF[3]*(P[7][1] + P[4][1]*dt) + SF[6]*(P[7][2] + P[4][2]*dt) + SPP[4]*(P[7][10] + P[4][10]*dt) - SPP[5]*(P[7][11] + P[4][11]*dt) - (q0*(P[7][12] + P[4][12]*dt))/2;
- nextP[7][4] = P[7][4] + P[4][4]*dt + SF[0]*(P[7][1] + P[4][1]*dt) + SF[2]*(P[7][0] + P[4][0]*dt) + SPP[0]*(P[7][2] + P[4][2]*dt) - SPP[2]*(P[7][3] + P[4][3]*dt);
- nextP[7][5] = P[7][5] + P[4][5]*dt + SF[1]*(P[7][0] + P[4][0]*dt) + SF[0]*(P[7][2] + P[4][2]*dt) + SF[2]*(P[7][3] + P[4][3]*dt) - SPP[0]*(P[7][1] + P[4][1]*dt);
- nextP[7][6] = P[7][6] + P[4][6]*dt + SF[1]*(P[7][1] + P[4][1]*dt) + SF[0]*(P[7][3] + P[4][3]*dt) + SPP[0]*(P[7][0] + P[4][0]*dt) - SPP[1]*(P[7][2] + P[4][2]*dt);
- nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt);
- nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt);
- nextP[7][9] = P[7][9] + P[4][9]*dt + dt*(P[7][6] + P[4][6]*dt);
- nextP[7][10] = P[7][10] + P[4][10]*dt;
- nextP[7][11] = P[7][11] + P[4][11]*dt;
- nextP[7][12] = P[7][12] + P[4][12]*dt;
- nextP[7][13] = P[7][13] + P[4][13]*dt;
- nextP[7][14] = P[7][14] + P[4][14]*dt;
- nextP[7][15] = P[7][15] + P[4][15]*dt;
- nextP[7][16] = P[7][16] + P[4][16]*dt;
- nextP[7][17] = P[7][17] + P[4][17]*dt;
- nextP[7][18] = P[7][18] + P[4][18]*dt;
- nextP[7][19] = P[7][19] + P[4][19]*dt;
- nextP[7][20] = P[7][20] + P[4][20]*dt;
- nextP[8][0] = P[8][0] + P[5][0]*dt + SF[6]*(P[8][1] + P[5][1]*dt) + SPP[7]*(P[8][2] + P[5][2]*dt) + SPP[6]*(P[8][3] + P[5][3]*dt) + SPP[5]*(P[8][10] + P[5][10]*dt) + SPP[4]*(P[8][11] + P[5][11]*dt) + SPP[3]*(P[8][12] + P[5][12]*dt);
- nextP[8][1] = P[8][1] + P[5][1]*dt + SF[5]*(P[8][0] + P[5][0]*dt) + SF[4]*(P[8][2] + P[5][2]*dt) + SPP[7]*(P[8][3] + P[5][3]*dt) + SPP[3]*(P[8][11] + P[5][11]*dt) - SPP[4]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][10] + P[5][10]*dt))/2;
- nextP[8][2] = P[8][2] + P[5][2]*dt + SF[3]*(P[8][0] + P[5][0]*dt) + SF[5]*(P[8][3] + P[5][3]*dt) + SPP[6]*(P[8][1] + P[5][1]*dt) - SPP[3]*(P[8][10] + P[5][10]*dt) + SPP[5]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][11] + P[5][11]*dt))/2;
- nextP[8][3] = P[8][3] + P[5][3]*dt + SF[4]*(P[8][0] + P[5][0]*dt) + SF[3]*(P[8][1] + P[5][1]*dt) + SF[6]*(P[8][2] + P[5][2]*dt) + SPP[4]*(P[8][10] + P[5][10]*dt) - SPP[5]*(P[8][11] + P[5][11]*dt) - (q0*(P[8][12] + P[5][12]*dt))/2;
- nextP[8][4] = P[8][4] + P[5][4]*dt + SF[0]*(P[8][1] + P[5][1]*dt) + SF[2]*(P[8][0] + P[5][0]*dt) + SPP[0]*(P[8][2] + P[5][2]*dt) - SPP[2]*(P[8][3] + P[5][3]*dt);
- nextP[8][5] = P[8][5] + P[5][5]*dt + SF[1]*(P[8][0] + P[5][0]*dt) + SF[0]*(P[8][2] + P[5][2]*dt) + SF[2]*(P[8][3] + P[5][3]*dt) - SPP[0]*(P[8][1] + P[5][1]*dt);
- nextP[8][6] = P[8][6] + P[5][6]*dt + SF[1]*(P[8][1] + P[5][1]*dt) + SF[0]*(P[8][3] + P[5][3]*dt) + SPP[0]*(P[8][0] + P[5][0]*dt) - SPP[1]*(P[8][2] + P[5][2]*dt);
- nextP[8][7] = P[8][7] + P[5][7]*dt + dt*(P[8][4] + P[5][4]*dt);
- nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt);
- nextP[8][9] = P[8][9] + P[5][9]*dt + dt*(P[8][6] + P[5][6]*dt);
- nextP[8][10] = P[8][10] + P[5][10]*dt;
- nextP[8][11] = P[8][11] + P[5][11]*dt;
- nextP[8][12] = P[8][12] + P[5][12]*dt;
- nextP[8][13] = P[8][13] + P[5][13]*dt;
- nextP[8][14] = P[8][14] + P[5][14]*dt;
- nextP[8][15] = P[8][15] + P[5][15]*dt;
- nextP[8][16] = P[8][16] + P[5][16]*dt;
- nextP[8][17] = P[8][17] + P[5][17]*dt;
- nextP[8][18] = P[8][18] + P[5][18]*dt;
- nextP[8][19] = P[8][19] + P[5][19]*dt;
- nextP[8][20] = P[8][20] + P[5][20]*dt;
- nextP[9][0] = P[9][0] + P[6][0]*dt + SF[6]*(P[9][1] + P[6][1]*dt) + SPP[7]*(P[9][2] + P[6][2]*dt) + SPP[6]*(P[9][3] + P[6][3]*dt) + SPP[5]*(P[9][10] + P[6][10]*dt) + SPP[4]*(P[9][11] + P[6][11]*dt) + SPP[3]*(P[9][12] + P[6][12]*dt);
- nextP[9][1] = P[9][1] + P[6][1]*dt + SF[5]*(P[9][0] + P[6][0]*dt) + SF[4]*(P[9][2] + P[6][2]*dt) + SPP[7]*(P[9][3] + P[6][3]*dt) + SPP[3]*(P[9][11] + P[6][11]*dt) - SPP[4]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][10] + P[6][10]*dt))/2;
- nextP[9][2] = P[9][2] + P[6][2]*dt + SF[3]*(P[9][0] + P[6][0]*dt) + SF[5]*(P[9][3] + P[6][3]*dt) + SPP[6]*(P[9][1] + P[6][1]*dt) - SPP[3]*(P[9][10] + P[6][10]*dt) + SPP[5]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][11] + P[6][11]*dt))/2;
- nextP[9][3] = P[9][3] + P[6][3]*dt + SF[4]*(P[9][0] + P[6][0]*dt) + SF[3]*(P[9][1] + P[6][1]*dt) + SF[6]*(P[9][2] + P[6][2]*dt) + SPP[4]*(P[9][10] + P[6][10]*dt) - SPP[5]*(P[9][11] + P[6][11]*dt) - (q0*(P[9][12] + P[6][12]*dt))/2;
- nextP[9][4] = P[9][4] + P[6][4]*dt + SF[0]*(P[9][1] + P[6][1]*dt) + SF[2]*(P[9][0] + P[6][0]*dt) + SPP[0]*(P[9][2] + P[6][2]*dt) - SPP[2]*(P[9][3] + P[6][3]*dt);
- nextP[9][5] = P[9][5] + P[6][5]*dt + SF[1]*(P[9][0] + P[6][0]*dt) + SF[0]*(P[9][2] + P[6][2]*dt) + SF[2]*(P[9][3] + P[6][3]*dt) - SPP[0]*(P[9][1] + P[6][1]*dt);
- nextP[9][6] = P[9][6] + P[6][6]*dt + SF[1]*(P[9][1] + P[6][1]*dt) + SF[0]*(P[9][3] + P[6][3]*dt) + SPP[0]*(P[9][0] + P[6][0]*dt) - SPP[1]*(P[9][2] + P[6][2]*dt);
- nextP[9][7] = P[9][7] + P[6][7]*dt + dt*(P[9][4] + P[6][4]*dt);
- nextP[9][8] = P[9][8] + P[6][8]*dt + dt*(P[9][5] + P[6][5]*dt);
- nextP[9][9] = P[9][9] + P[6][9]*dt + dt*(P[9][6] + P[6][6]*dt);
- nextP[9][10] = P[9][10] + P[6][10]*dt;
- nextP[9][11] = P[9][11] + P[6][11]*dt;
- nextP[9][12] = P[9][12] + P[6][12]*dt;
- nextP[9][13] = P[9][13] + P[6][13]*dt;
- nextP[9][14] = P[9][14] + P[6][14]*dt;
- nextP[9][15] = P[9][15] + P[6][15]*dt;
- nextP[9][16] = P[9][16] + P[6][16]*dt;
- nextP[9][17] = P[9][17] + P[6][17]*dt;
- nextP[9][18] = P[9][18] + P[6][18]*dt;
- nextP[9][19] = P[9][19] + P[6][19]*dt;
- nextP[9][20] = P[9][20] + P[6][20]*dt;
- nextP[10][0] = P[10][0] + P[10][1]*SF[6] + P[10][2]*SPP[7] + P[10][3]*SPP[6] + P[10][10]*SPP[5] + P[10][11]*SPP[4] + P[10][12]*SPP[3];
- nextP[10][1] = P[10][1] + P[10][0]*SF[5] + P[10][2]*SF[4] + P[10][3]*SPP[7] + P[10][11]*SPP[3] - P[10][12]*SPP[4] - (P[10][10]*q0)/2;
- nextP[10][2] = P[10][2] + P[10][0]*SF[3] + P[10][3]*SF[5] + P[10][1]*SPP[6] - P[10][10]*SPP[3] + P[10][12]*SPP[5] - (P[10][11]*q0)/2;
- nextP[10][3] = P[10][3] + P[10][0]*SF[4] + P[10][1]*SF[3] + P[10][2]*SF[6] + P[10][10]*SPP[4] - P[10][11]*SPP[5] - (P[10][12]*q0)/2;
- nextP[10][4] = P[10][4] + P[10][1]*SF[0] + P[10][0]*SF[2] + P[10][2]*SPP[0] - P[10][3]*SPP[2];
- nextP[10][5] = P[10][5] + P[10][0]*SF[1] + P[10][2]*SF[0] + P[10][3]*SF[2] - P[10][1]*SPP[0];
- nextP[10][6] = P[10][6] + P[10][1]*SF[1] + P[10][3]*SF[0] + P[10][0]*SPP[0] - P[10][2]*SPP[1];
- nextP[10][7] = P[10][7] + P[10][4]*dt;
- nextP[10][8] = P[10][8] + P[10][5]*dt;
- nextP[10][9] = P[10][9] + P[10][6]*dt;
- nextP[10][10] = P[10][10];
- nextP[10][11] = P[10][11];
- nextP[10][12] = P[10][12];
- nextP[10][13] = P[10][13];
- nextP[10][14] = P[10][14];
- nextP[10][15] = P[10][15];
- nextP[10][16] = P[10][16];
- nextP[10][17] = P[10][17];
- nextP[10][18] = P[10][18];
- nextP[10][19] = P[10][19];
- nextP[10][20] = P[10][20];
- nextP[11][0] = P[11][0] + P[11][1]*SF[6] + P[11][2]*SPP[7] + P[11][3]*SPP[6] + P[11][10]*SPP[5] + P[11][11]*SPP[4] + P[11][12]*SPP[3];
- nextP[11][1] = P[11][1] + P[11][0]*SF[5] + P[11][2]*SF[4] + P[11][3]*SPP[7] + P[11][11]*SPP[3] - P[11][12]*SPP[4] - (P[11][10]*q0)/2;
- nextP[11][2] = P[11][2] + P[11][0]*SF[3] + P[11][3]*SF[5] + P[11][1]*SPP[6] - P[11][10]*SPP[3] + P[11][12]*SPP[5] - (P[11][11]*q0)/2;
- nextP[11][3] = P[11][3] + P[11][0]*SF[4] + P[11][1]*SF[3] + P[11][2]*SF[6] + P[11][10]*SPP[4] - P[11][11]*SPP[5] - (P[11][12]*q0)/2;
- nextP[11][4] = P[11][4] + P[11][1]*SF[0] + P[11][0]*SF[2] + P[11][2]*SPP[0] - P[11][3]*SPP[2];
- nextP[11][5] = P[11][5] + P[11][0]*SF[1] + P[11][2]*SF[0] + P[11][3]*SF[2] - P[11][1]*SPP[0];
- nextP[11][6] = P[11][6] + P[11][1]*SF[1] + P[11][3]*SF[0] + P[11][0]*SPP[0] - P[11][2]*SPP[1];
- nextP[11][7] = P[11][7] + P[11][4]*dt;
- nextP[11][8] = P[11][8] + P[11][5]*dt;
- nextP[11][9] = P[11][9] + P[11][6]*dt;
- nextP[11][10] = P[11][10];
- nextP[11][11] = P[11][11];
- nextP[11][12] = P[11][12];
- nextP[11][13] = P[11][13];
- nextP[11][14] = P[11][14];
- nextP[11][15] = P[11][15];
- nextP[11][16] = P[11][16];
- nextP[11][17] = P[11][17];
- nextP[11][18] = P[11][18];
- nextP[11][19] = P[11][19];
- nextP[11][20] = P[11][20];
- nextP[12][0] = P[12][0] + P[12][1]*SF[6] + P[12][2]*SPP[7] + P[12][3]*SPP[6] + P[12][10]*SPP[5] + P[12][11]*SPP[4] + P[12][12]*SPP[3];
- nextP[12][1] = P[12][1] + P[12][0]*SF[5] + P[12][2]*SF[4] + P[12][3]*SPP[7] + P[12][11]*SPP[3] - P[12][12]*SPP[4] - (P[12][10]*q0)/2;
- nextP[12][2] = P[12][2] + P[12][0]*SF[3] + P[12][3]*SF[5] + P[12][1]*SPP[6] - P[12][10]*SPP[3] + P[12][12]*SPP[5] - (P[12][11]*q0)/2;
- nextP[12][3] = P[12][3] + P[12][0]*SF[4] + P[12][1]*SF[3] + P[12][2]*SF[6] + P[12][10]*SPP[4] - P[12][11]*SPP[5] - (P[12][12]*q0)/2;
- nextP[12][4] = P[12][4] + P[12][1]*SF[0] + P[12][0]*SF[2] + P[12][2]*SPP[0] - P[12][3]*SPP[2];
- nextP[12][5] = P[12][5] + P[12][0]*SF[1] + P[12][2]*SF[0] + P[12][3]*SF[2] - P[12][1]*SPP[0];
- nextP[12][6] = P[12][6] + P[12][1]*SF[1] + P[12][3]*SF[0] + P[12][0]*SPP[0] - P[12][2]*SPP[1];
- nextP[12][7] = P[12][7] + P[12][4]*dt;
- nextP[12][8] = P[12][8] + P[12][5]*dt;
- nextP[12][9] = P[12][9] + P[12][6]*dt;
- nextP[12][10] = P[12][10];
- nextP[12][11] = P[12][11];
- nextP[12][12] = P[12][12];
- nextP[12][13] = P[12][13];
- nextP[12][14] = P[12][14];
- nextP[12][15] = P[12][15];
- nextP[12][16] = P[12][16];
- nextP[12][17] = P[12][17];
- nextP[12][18] = P[12][18];
- nextP[12][19] = P[12][19];
- nextP[12][20] = P[12][20];
- nextP[13][0] = P[13][0] + P[13][1]*SF[6] + P[13][2]*SPP[7] + P[13][3]*SPP[6] + P[13][10]*SPP[5] + P[13][11]*SPP[4] + P[13][12]*SPP[3];
- nextP[13][1] = P[13][1] + P[13][0]*SF[5] + P[13][2]*SF[4] + P[13][3]*SPP[7] + P[13][11]*SPP[3] - P[13][12]*SPP[4] - (P[13][10]*q0)/2;
- nextP[13][2] = P[13][2] + P[13][0]*SF[3] + P[13][3]*SF[5] + P[13][1]*SPP[6] - P[13][10]*SPP[3] + P[13][12]*SPP[5] - (P[13][11]*q0)/2;
- nextP[13][3] = P[13][3] + P[13][0]*SF[4] + P[13][1]*SF[3] + P[13][2]*SF[6] + P[13][10]*SPP[4] - P[13][11]*SPP[5] - (P[13][12]*q0)/2;
- nextP[13][4] = P[13][4] + P[13][1]*SF[0] + P[13][0]*SF[2] + P[13][2]*SPP[0] - P[13][3]*SPP[2];
- nextP[13][5] = P[13][5] + P[13][0]*SF[1] + P[13][2]*SF[0] + P[13][3]*SF[2] - P[13][1]*SPP[0];
- nextP[13][6] = P[13][6] + P[13][1]*SF[1] + P[13][3]*SF[0] + P[13][0]*SPP[0] - P[13][2]*SPP[1];
- nextP[13][7] = P[13][7] + P[13][4]*dt;
- nextP[13][8] = P[13][8] + P[13][5]*dt;
- nextP[13][9] = P[13][9] + P[13][6]*dt;
- nextP[13][10] = P[13][10];
- nextP[13][11] = P[13][11];
- nextP[13][12] = P[13][12];
- nextP[13][13] = P[13][13];
- nextP[13][14] = P[13][14];
- nextP[13][15] = P[13][15];
- nextP[13][16] = P[13][16];
- nextP[13][17] = P[13][17];
- nextP[13][18] = P[13][18];
- nextP[13][19] = P[13][19];
- nextP[13][20] = P[13][20];
- nextP[14][0] = P[14][0] + P[14][1]*SF[6] + P[14][2]*SPP[7] + P[14][3]*SPP[6] + P[14][10]*SPP[5] + P[14][11]*SPP[4] + P[14][12]*SPP[3];
- nextP[14][1] = P[14][1] + P[14][0]*SF[5] + P[14][2]*SF[4] + P[14][3]*SPP[7] + P[14][11]*SPP[3] - P[14][12]*SPP[4] - (P[14][10]*q0)/2;
- nextP[14][2] = P[14][2] + P[14][0]*SF[3] + P[14][3]*SF[5] + P[14][1]*SPP[6] - P[14][10]*SPP[3] + P[14][12]*SPP[5] - (P[14][11]*q0)/2;
- nextP[14][3] = P[14][3] + P[14][0]*SF[4] + P[14][1]*SF[3] + P[14][2]*SF[6] + P[14][10]*SPP[4] - P[14][11]*SPP[5] - (P[14][12]*q0)/2;
- nextP[14][4] = P[14][4] + P[14][1]*SF[0] + P[14][0]*SF[2] + P[14][2]*SPP[0] - P[14][3]*SPP[2];
- nextP[14][5] = P[14][5] + P[14][0]*SF[1] + P[14][2]*SF[0] + P[14][3]*SF[2] - P[14][1]*SPP[0];
- nextP[14][6] = P[14][6] + P[14][1]*SF[1] + P[14][3]*SF[0] + P[14][0]*SPP[0] - P[14][2]*SPP[1];
- nextP[14][7] = P[14][7] + P[14][4]*dt;
- nextP[14][8] = P[14][8] + P[14][5]*dt;
- nextP[14][9] = P[14][9] + P[14][6]*dt;
- nextP[14][10] = P[14][10];
- nextP[14][11] = P[14][11];
- nextP[14][12] = P[14][12];
- nextP[14][13] = P[14][13];
- nextP[14][14] = P[14][14];
- nextP[14][15] = P[14][15];
- nextP[14][16] = P[14][16];
- nextP[14][17] = P[14][17];
- nextP[14][18] = P[14][18];
- nextP[14][19] = P[14][19];
- nextP[14][20] = P[14][20];
- nextP[15][0] = P[15][0] + P[15][1]*SF[6] + P[15][2]*SPP[7] + P[15][3]*SPP[6] + P[15][10]*SPP[5] + P[15][11]*SPP[4] + P[15][12]*SPP[3];
- nextP[15][1] = P[15][1] + P[15][0]*SF[5] + P[15][2]*SF[4] + P[15][3]*SPP[7] + P[15][11]*SPP[3] - P[15][12]*SPP[4] - (P[15][10]*q0)/2;
- nextP[15][2] = P[15][2] + P[15][0]*SF[3] + P[15][3]*SF[5] + P[15][1]*SPP[6] - P[15][10]*SPP[3] + P[15][12]*SPP[5] - (P[15][11]*q0)/2;
- nextP[15][3] = P[15][3] + P[15][0]*SF[4] + P[15][1]*SF[3] + P[15][2]*SF[6] + P[15][10]*SPP[4] - P[15][11]*SPP[5] - (P[15][12]*q0)/2;
- nextP[15][4] = P[15][4] + P[15][1]*SF[0] + P[15][0]*SF[2] + P[15][2]*SPP[0] - P[15][3]*SPP[2];
- nextP[15][5] = P[15][5] + P[15][0]*SF[1] + P[15][2]*SF[0] + P[15][3]*SF[2] - P[15][1]*SPP[0];
- nextP[15][6] = P[15][6] + P[15][1]*SF[1] + P[15][3]*SF[0] + P[15][0]*SPP[0] - P[15][2]*SPP[1];
- nextP[15][7] = P[15][7] + P[15][4]*dt;
- nextP[15][8] = P[15][8] + P[15][5]*dt;
- nextP[15][9] = P[15][9] + P[15][6]*dt;
- nextP[15][10] = P[15][10];
- nextP[15][11] = P[15][11];
- nextP[15][12] = P[15][12];
- nextP[15][13] = P[15][13];
- nextP[15][14] = P[15][14];
- nextP[15][15] = P[15][15];
- nextP[15][16] = P[15][16];
- nextP[15][17] = P[15][17];
- nextP[15][18] = P[15][18];
- nextP[15][19] = P[15][19];
- nextP[15][20] = P[15][20];
- nextP[16][0] = P[16][0] + P[16][1]*SF[6] + P[16][2]*SPP[7] + P[16][3]*SPP[6] + P[16][10]*SPP[5] + P[16][11]*SPP[4] + P[16][12]*SPP[3];
- nextP[16][1] = P[16][1] + P[16][0]*SF[5] + P[16][2]*SF[4] + P[16][3]*SPP[7] + P[16][11]*SPP[3] - P[16][12]*SPP[4] - (P[16][10]*q0)/2;
- nextP[16][2] = P[16][2] + P[16][0]*SF[3] + P[16][3]*SF[5] + P[16][1]*SPP[6] - P[16][10]*SPP[3] + P[16][12]*SPP[5] - (P[16][11]*q0)/2;
- nextP[16][3] = P[16][3] + P[16][0]*SF[4] + P[16][1]*SF[3] + P[16][2]*SF[6] + P[16][10]*SPP[4] - P[16][11]*SPP[5] - (P[16][12]*q0)/2;
- nextP[16][4] = P[16][4] + P[16][1]*SF[0] + P[16][0]*SF[2] + P[16][2]*SPP[0] - P[16][3]*SPP[2];
- nextP[16][5] = P[16][5] + P[16][0]*SF[1] + P[16][2]*SF[0] + P[16][3]*SF[2] - P[16][1]*SPP[0];
- nextP[16][6] = P[16][6] + P[16][1]*SF[1] + P[16][3]*SF[0] + P[16][0]*SPP[0] - P[16][2]*SPP[1];
- nextP[16][7] = P[16][7] + P[16][4]*dt;
- nextP[16][8] = P[16][8] + P[16][5]*dt;
- nextP[16][9] = P[16][9] + P[16][6]*dt;
- nextP[16][10] = P[16][10];
- nextP[16][11] = P[16][11];
- nextP[16][12] = P[16][12];
- nextP[16][13] = P[16][13];
- nextP[16][14] = P[16][14];
- nextP[16][15] = P[16][15];
- nextP[16][16] = P[16][16];
- nextP[16][17] = P[16][17];
- nextP[16][18] = P[16][18];
- nextP[16][19] = P[16][19];
- nextP[16][20] = P[16][20];
- nextP[17][0] = P[17][0] + P[17][1]*SF[6] + P[17][2]*SPP[7] + P[17][3]*SPP[6] + P[17][10]*SPP[5] + P[17][11]*SPP[4] + P[17][12]*SPP[3];
- nextP[17][1] = P[17][1] + P[17][0]*SF[5] + P[17][2]*SF[4] + P[17][3]*SPP[7] + P[17][11]*SPP[3] - P[17][12]*SPP[4] - (P[17][10]*q0)/2;
- nextP[17][2] = P[17][2] + P[17][0]*SF[3] + P[17][3]*SF[5] + P[17][1]*SPP[6] - P[17][10]*SPP[3] + P[17][12]*SPP[5] - (P[17][11]*q0)/2;
- nextP[17][3] = P[17][3] + P[17][0]*SF[4] + P[17][1]*SF[3] + P[17][2]*SF[6] + P[17][10]*SPP[4] - P[17][11]*SPP[5] - (P[17][12]*q0)/2;
- nextP[17][4] = P[17][4] + P[17][1]*SF[0] + P[17][0]*SF[2] + P[17][2]*SPP[0] - P[17][3]*SPP[2];
- nextP[17][5] = P[17][5] + P[17][0]*SF[1] + P[17][2]*SF[0] + P[17][3]*SF[2] - P[17][1]*SPP[0];
- nextP[17][6] = P[17][6] + P[17][1]*SF[1] + P[17][3]*SF[0] + P[17][0]*SPP[0] - P[17][2]*SPP[1];
- nextP[17][7] = P[17][7] + P[17][4]*dt;
- nextP[17][8] = P[17][8] + P[17][5]*dt;
- nextP[17][9] = P[17][9] + P[17][6]*dt;
- nextP[17][10] = P[17][10];
- nextP[17][11] = P[17][11];
- nextP[17][12] = P[17][12];
- nextP[17][13] = P[17][13];
- nextP[17][14] = P[17][14];
- nextP[17][15] = P[17][15];
- nextP[17][16] = P[17][16];
- nextP[17][17] = P[17][17];
- nextP[17][18] = P[17][18];
- nextP[17][19] = P[17][19];
- nextP[17][20] = P[17][20];
- nextP[18][0] = P[18][0] + P[18][1]*SF[6] + P[18][2]*SPP[7] + P[18][3]*SPP[6] + P[18][10]*SPP[5] + P[18][11]*SPP[4] + P[18][12]*SPP[3];
- nextP[18][1] = P[18][1] + P[18][0]*SF[5] + P[18][2]*SF[4] + P[18][3]*SPP[7] + P[18][11]*SPP[3] - P[18][12]*SPP[4] - (P[18][10]*q0)/2;
- nextP[18][2] = P[18][2] + P[18][0]*SF[3] + P[18][3]*SF[5] + P[18][1]*SPP[6] - P[18][10]*SPP[3] + P[18][12]*SPP[5] - (P[18][11]*q0)/2;
- nextP[18][3] = P[18][3] + P[18][0]*SF[4] + P[18][1]*SF[3] + P[18][2]*SF[6] + P[18][10]*SPP[4] - P[18][11]*SPP[5] - (P[18][12]*q0)/2;
- nextP[18][4] = P[18][4] + P[18][1]*SF[0] + P[18][0]*SF[2] + P[18][2]*SPP[0] - P[18][3]*SPP[2];
- nextP[18][5] = P[18][5] + P[18][0]*SF[1] + P[18][2]*SF[0] + P[18][3]*SF[2] - P[18][1]*SPP[0];
- nextP[18][6] = P[18][6] + P[18][1]*SF[1] + P[18][3]*SF[0] + P[18][0]*SPP[0] - P[18][2]*SPP[1];
- nextP[18][7] = P[18][7] + P[18][4]*dt;
- nextP[18][8] = P[18][8] + P[18][5]*dt;
- nextP[18][9] = P[18][9] + P[18][6]*dt;
- nextP[18][10] = P[18][10];
- nextP[18][11] = P[18][11];
- nextP[18][12] = P[18][12];
- nextP[18][13] = P[18][13];
- nextP[18][14] = P[18][14];
- nextP[18][15] = P[18][15];
- nextP[18][16] = P[18][16];
- nextP[18][17] = P[18][17];
- nextP[18][18] = P[18][18];
- nextP[18][19] = P[18][19];
- nextP[18][20] = P[18][20];
- nextP[19][0] = P[19][0] + P[19][1]*SF[6] + P[19][2]*SPP[7] + P[19][3]*SPP[6] + P[19][10]*SPP[5] + P[19][11]*SPP[4] + P[19][12]*SPP[3];
- nextP[19][1] = P[19][1] + P[19][0]*SF[5] + P[19][2]*SF[4] + P[19][3]*SPP[7] + P[19][11]*SPP[3] - P[19][12]*SPP[4] - (P[19][10]*q0)/2;
- nextP[19][2] = P[19][2] + P[19][0]*SF[3] + P[19][3]*SF[5] + P[19][1]*SPP[6] - P[19][10]*SPP[3] + P[19][12]*SPP[5] - (P[19][11]*q0)/2;
- nextP[19][3] = P[19][3] + P[19][0]*SF[4] + P[19][1]*SF[3] + P[19][2]*SF[6] + P[19][10]*SPP[4] - P[19][11]*SPP[5] - (P[19][12]*q0)/2;
- nextP[19][4] = P[19][4] + P[19][1]*SF[0] + P[19][0]*SF[2] + P[19][2]*SPP[0] - P[19][3]*SPP[2];
- nextP[19][5] = P[19][5] + P[19][0]*SF[1] + P[19][2]*SF[0] + P[19][3]*SF[2] - P[19][1]*SPP[0];
- nextP[19][6] = P[19][6] + P[19][1]*SF[1] + P[19][3]*SF[0] + P[19][0]*SPP[0] - P[19][2]*SPP[1];
- nextP[19][7] = P[19][7] + P[19][4]*dt;
- nextP[19][8] = P[19][8] + P[19][5]*dt;
- nextP[19][9] = P[19][9] + P[19][6]*dt;
- nextP[19][10] = P[19][10];
- nextP[19][11] = P[19][11];
- nextP[19][12] = P[19][12];
- nextP[19][13] = P[19][13];
- nextP[19][14] = P[19][14];
- nextP[19][15] = P[19][15];
- nextP[19][16] = P[19][16];
- nextP[19][17] = P[19][17];
- nextP[19][18] = P[19][18];
- nextP[19][19] = P[19][19];
- nextP[19][20] = P[19][20];
- nextP[20][0] = P[20][0] + P[20][1]*SF[6] + P[20][2]*SPP[7] + P[20][3]*SPP[6] + P[20][10]*SPP[5] + P[20][11]*SPP[4] + P[20][12]*SPP[3];
- nextP[20][1] = P[20][1] + P[20][0]*SF[5] + P[20][2]*SF[4] + P[20][3]*SPP[7] + P[20][11]*SPP[3] - P[20][12]*SPP[4] - (P[20][10]*q0)/2;
- nextP[20][2] = P[20][2] + P[20][0]*SF[3] + P[20][3]*SF[5] + P[20][1]*SPP[6] - P[20][10]*SPP[3] + P[20][12]*SPP[5] - (P[20][11]*q0)/2;
- nextP[20][3] = P[20][3] + P[20][0]*SF[4] + P[20][1]*SF[3] + P[20][2]*SF[6] + P[20][10]*SPP[4] - P[20][11]*SPP[5] - (P[20][12]*q0)/2;
- nextP[20][4] = P[20][4] + P[20][1]*SF[0] + P[20][0]*SF[2] + P[20][2]*SPP[0] - P[20][3]*SPP[2];
- nextP[20][5] = P[20][5] + P[20][0]*SF[1] + P[20][2]*SF[0] + P[20][3]*SF[2] - P[20][1]*SPP[0];
- nextP[20][6] = P[20][6] + P[20][1]*SF[1] + P[20][3]*SF[0] + P[20][0]*SPP[0] - P[20][2]*SPP[1];
- nextP[20][7] = P[20][7] + P[20][4]*dt;
- nextP[20][8] = P[20][8] + P[20][5]*dt;
- nextP[20][9] = P[20][9] + P[20][6]*dt;
- nextP[20][10] = P[20][10];
- nextP[20][11] = P[20][11];
- nextP[20][12] = P[20][12];
- nextP[20][13] = P[20][13];
- nextP[20][14] = P[20][14];
- nextP[20][15] = P[20][15];
- nextP[20][16] = P[20][16];
- nextP[20][17] = P[20][17];
- nextP[20][18] = P[20][18];
- nextP[20][19] = P[20][19];
- nextP[20][20] = P[20][20];
-
- for (unsigned i = 0; i < n_states; i++)
- {
- nextP[i][i] = nextP[i][i] + processNoise[i];
- }
-
- // If on ground or no magnetometer fitted, inhibit magnetometer bias updates by
- // setting the coresponding covariance terms to zero.
- if (onGround || !useCompass)
- {
- zeroRows(nextP,15,20);
- zeroCols(nextP,15,20);
- }
-
- // If on ground or not using airspeed sensing, inhibit wind velocity
- // covariance growth.
- if (onGround || !useAirspeed)
- {
- zeroRows(nextP,13,14);
- zeroCols(nextP,13,14);
- }
-
- // If the total position variance exceds 1E6 (1000m), then stop covariance
- // growth by setting the predicted to the previous values
- // This prevent an ill conditioned matrix from occurring for long periods
- // without GPS
- if ((P[7][7] + P[8][8]) > 1E6f)
- {
- for (uint8_t i=7; i<=8; i++)
- {
- for (unsigned j = 0; j < n_states; j++)
- {
- nextP[i][j] = P[i][j];
- nextP[j][i] = P[j][i];
- }
- }
- }
-
- if (onGround || staticMode) {
- // copy the portion of the variances we want to
- // propagate
- for (unsigned i = 0; i < 14; i++) {
- P[i][i] = nextP[i][i];
-
- // force symmetry for observable states
- // force zero for non-observable states
- for (unsigned i = 1; i < n_states; i++)
- {
- for (uint8_t j = 0; j < i; j++)
- {
- if ((i > 12) || (j > 12)) {
- P[i][j] = 0.0f;
- } else {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- }
- P[j][i] = P[i][j];
- }
- }
- }
-
- } else {
-
- // Copy covariance
- for (unsigned i = 0; i < n_states; i++) {
- P[i][i] = nextP[i][i];
- }
-
- // force symmetry for observable states
- for (unsigned i = 1; i < n_states; i++)
- {
- for (uint8_t j = 0; j < i; j++)
- {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- P[j][i] = P[i][j];
- }
- }
-
- }
-
- ConstrainVariances();
-}
-
-void AttPosEKF::FuseVelposNED()
-{
-
-// declare variables used by fault isolation logic
- uint32_t gpsRetryTime = 30000; // time in msec before GPS fusion will be retried following innovation consistency failure
- uint32_t gpsRetryTimeNoTAS = 5000; // retry time if no TAS measurement available
- uint32_t hgtRetryTime = 5000; // height measurement retry time
- uint32_t horizRetryTime;
-
-// declare variables used to check measurement errors
- float velInnov[3] = {0.0f,0.0f,0.0f};
- float posInnov[2] = {0.0f,0.0f};
- float hgtInnov = 0.0f;
-
-// declare variables used to control access to arrays
- bool fuseData[6] = {false,false,false,false,false,false};
- uint8_t stateIndex;
- uint8_t obsIndex;
- uint8_t indexLimit;
-
-// declare variables used by state and covariance update calculations
- float velErr;
- float posErr;
- float R_OBS[6];
- float observation[6];
- float SK;
- float quatMag;
-
-// Perform sequential fusion of GPS measurements. This assumes that the
-// errors in the different velocity and position components are
-// uncorrelated which is not true, however in the absence of covariance
-// data from the GPS receiver it is the only assumption we can make
-// so we might as well take advantage of the computational efficiencies
-// associated with sequential fusion
- if (fuseVelData || fusePosData || fuseHgtData)
- {
- // set the GPS data timeout depending on whether airspeed data is present
- if (useAirspeed) horizRetryTime = gpsRetryTime;
- else horizRetryTime = gpsRetryTimeNoTAS;
-
- // Form the observation vector
- for (uint8_t i=0; i<=2; i++) observation[i] = velNED[i];
- for (uint8_t i=3; i<=4; i++) observation[i] = posNE[i-3];
- observation[5] = -(hgtMea);
-
- // Estimate the GPS Velocity, GPS horiz position and height measurement variances.
- velErr = 0.2f*accNavMag; // additional error in GPS velocities caused by manoeuvring
- posErr = 0.2f*accNavMag; // additional error in GPS position caused by manoeuvring
- R_OBS[0] = 0.04f + sq(velErr);
- R_OBS[1] = R_OBS[0];
- R_OBS[2] = 0.08f + sq(velErr);
- R_OBS[3] = R_OBS[2];
- R_OBS[4] = 4.0f + sq(posErr);
- R_OBS[5] = 4.0f;
-
- // Set innovation variances to zero default
- for (uint8_t i = 0; i<=5; i++)
- {
- varInnovVelPos[i] = 0.0f;
- }
- // calculate innovations and check GPS data validity using an innovation consistency check
- if (fuseVelData)
- {
- // test velocity measurements
- uint8_t imax = 2;
- if (fusionModeGPS == 1) imax = 1;
- for (uint8_t i = 0; i<=imax; i++)
- {
- velInnov[i] = statesAtVelTime[i+4] - velNED[i];
- stateIndex = 4 + i;
- varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS[i];
- }
- // apply a 5-sigma threshold
- current_ekf_state.velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0f * (varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]);
- current_ekf_state.velTimeout = (millis() - current_ekf_state.velFailTime) > horizRetryTime;
- if (current_ekf_state.velHealth || current_ekf_state.velTimeout)
- {
- current_ekf_state.velHealth = true;
- current_ekf_state.velFailTime = millis();
- }
- else
- {
- current_ekf_state.velHealth = false;
- }
- }
- if (fusePosData)
- {
- // test horizontal position measurements
- posInnov[0] = statesAtPosTime[7] - posNE[0];
- posInnov[1] = statesAtPosTime[8] - posNE[1];
- varInnovVelPos[3] = P[7][7] + R_OBS[3];
- varInnovVelPos[4] = P[8][8] + R_OBS[4];
- // apply a 10-sigma threshold
- current_ekf_state.posHealth = (sq(posInnov[0]) + sq(posInnov[1])) < 100.0f*(varInnovVelPos[3] + varInnovVelPos[4]);
- current_ekf_state.posTimeout = (millis() - current_ekf_state.posFailTime) > horizRetryTime;
- if (current_ekf_state.posHealth || current_ekf_state.posTimeout)
- {
- current_ekf_state.posHealth = true;
- current_ekf_state.posFailTime = millis();
- }
- else
- {
- current_ekf_state.posHealth = false;
- }
- }
- // test height measurements
- if (fuseHgtData)
- {
- hgtInnov = statesAtHgtTime[9] + hgtMea;
- varInnovVelPos[5] = P[9][9] + R_OBS[5];
- // apply a 10-sigma threshold
- current_ekf_state.hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5];
- current_ekf_state.hgtTimeout = (millis() - current_ekf_state.hgtFailTime) > hgtRetryTime;
- if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout)
- {
- current_ekf_state.hgtHealth = true;
- current_ekf_state.hgtFailTime = millis();
- }
- else
- {
- current_ekf_state.hgtHealth = false;
- }
- }
- // Set range for sequential fusion of velocity and position measurements depending
- // on which data is available and its health
- if (fuseVelData && fusionModeGPS == 0 && current_ekf_state.velHealth)
- {
- fuseData[0] = true;
- fuseData[1] = true;
- fuseData[2] = true;
- }
- if (fuseVelData && fusionModeGPS == 1 && current_ekf_state.velHealth)
- {
- fuseData[0] = true;
- fuseData[1] = true;
- }
- if (fusePosData && fusionModeGPS <= 2 && current_ekf_state.posHealth)
- {
- fuseData[3] = true;
- fuseData[4] = true;
- }
- if (fuseHgtData && current_ekf_state.hgtHealth)
- {
- fuseData[5] = true;
- }
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = 20;
- }
- else
- {
- indexLimit = 12;
- }
- // Fuse measurements sequentially
- for (obsIndex=0; obsIndex<=5; obsIndex++)
- {
- if (fuseData[obsIndex])
- {
- stateIndex = 4 + obsIndex;
- // Calculate the measurement innovation, using states from a
- // different time coordinate if fusing height data
- if (obsIndex >= 0 && obsIndex <= 2)
- {
- innovVelPos[obsIndex] = statesAtVelTime[stateIndex] - observation[obsIndex];
- }
- else if (obsIndex == 3 || obsIndex == 4)
- {
- innovVelPos[obsIndex] = statesAtPosTime[stateIndex] - observation[obsIndex];
- }
- else if (obsIndex == 5)
- {
- innovVelPos[obsIndex] = statesAtHgtTime[stateIndex] - observation[obsIndex];
- }
- // Calculate the Kalman Gain
- // Calculate innovation variances - also used for data logging
- varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
- SK = 1.0/varInnovVelPos[obsIndex];
- for (uint8_t i= 0; i<=indexLimit; i++)
- {
- Kfusion[i] = P[i][stateIndex]*SK;
- }
- // Calculate state corrections and re-normalise the quaternions
- for (uint8_t i = 0; i<=indexLimit; i++)
- {
- states[i] = states[i] - Kfusion[i] * innovVelPos[obsIndex];
- }
- quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
- if (quatMag > 1e-12f) // divide by 0 protection
- {
- for (uint8_t i = 0; i<=3; i++)
- {
- states[i] = states[i] / quatMag;
- }
- }
- // Update the covariance - take advantage of direct observation of a
- // single state at index = stateIndex to reduce computations
- // Optimised implementation of standard equation P = (I - K*H)*P;
- for (uint8_t i= 0; i<=indexLimit; i++)
- {
- for (uint8_t j= 0; j<=indexLimit; j++)
- {
- KHP[i][j] = Kfusion[i] * P[stateIndex][j];
- }
- }
- for (uint8_t i= 0; i<=indexLimit; i++)
- {
- for (uint8_t j= 0; j<=indexLimit; j++)
- {
- P[i][j] = P[i][j] - KHP[i][j];
- }
- }
- }
- }
- }
-
- ForceSymmetry();
- ConstrainVariances();
-
- //printf("velh: %s, posh: %s, hgth: %s\n", ((velHealth) ? "OK" : "FAIL"), ((posHealth) ? "OK" : "FAIL"), ((hgtHealth) ? "OK" : "FAIL"));
-}
-
-void AttPosEKF::FuseMagnetometer()
-{
- uint8_t obsIndex;
- uint8_t indexLimit;
- float DCM[3][3] =
- {
- {1.0f,0.0f,0.0f} ,
- {0.0f,1.0f,0.0f} ,
- {0.0f,0.0f,1.0f}
- };
- float MagPred[3] = {0.0f,0.0f,0.0f};
- float SK_MX[6];
- float SK_MY[5];
- float SK_MZ[6];
- float SH_MAG[9] = {0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f};
-
-// Perform sequential fusion of Magnetometer measurements.
-// This assumes that the errors in the different components are
-// uncorrelated which is not true, however in the absence of covariance
-// data fit is the only assumption we can make
-// so we might as well take advantage of the computational efficiencies
-// associated with sequential fusion
- if (useCompass && (fuseMagData || obsIndex == 1 || obsIndex == 2))
- {
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = 20;
- }
- else
- {
- indexLimit = 12;
- }
-
- static float q0 = 0.0f;
- static float q1 = 0.0f;
- static float q2 = 0.0f;
- static float q3 = 1.0f;
- static float magN = 0.4f;
- static float magE = 0.0f;
- static float magD = 0.3f;
-
- static float R_MAG = 0.0025f;
-
- float H_MAG[21] = {0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f};
-
- // Sequential fusion of XYZ components to spread processing load across
- // three prediction time steps.
-
- // Calculate observation jacobians and Kalman gains
- if (fuseMagData)
- {
- static float magXbias = 0.0f;
- static float magYbias = 0.0f;
- static float magZbias = 0.0f;
-
- // Copy required states to local variable names
- q0 = statesAtMagMeasTime[0];
- q1 = statesAtMagMeasTime[1];
- q2 = statesAtMagMeasTime[2];
- q3 = statesAtMagMeasTime[3];
- magN = statesAtMagMeasTime[15];
- magE = statesAtMagMeasTime[16];
- magD = statesAtMagMeasTime[17];
- magXbias = statesAtMagMeasTime[18];
- magYbias = statesAtMagMeasTime[19];
- magZbias = statesAtMagMeasTime[20];
-
- // rotate predicted earth components into body axes and calculate
- // predicted measurments
- DCM[0][0] = q0*q0 + q1*q1 - q2*q2 - q3*q3;
- DCM[0][1] = 2*(q1*q2 + q0*q3);
- DCM[0][2] = 2*(q1*q3-q0*q2);
- DCM[1][0] = 2*(q1*q2 - q0*q3);
- DCM[1][1] = q0*q0 - q1*q1 + q2*q2 - q3*q3;
- DCM[1][2] = 2*(q2*q3 + q0*q1);
- DCM[2][0] = 2*(q1*q3 + q0*q2);
- DCM[2][1] = 2*(q2*q3 - q0*q1);
- DCM[2][2] = q0*q0 - q1*q1 - q2*q2 + q3*q3;
- MagPred[0] = DCM[0][0]*magN + DCM[0][1]*magE + DCM[0][2]*magD + magXbias;
- MagPred[1] = DCM[1][0]*magN + DCM[1][1]*magE + DCM[1][2]*magD + magYbias;
- MagPred[2] = DCM[2][0]*magN + DCM[2][1]*magE + DCM[2][2]*magD + magZbias;
-
- // scale magnetometer observation error with total angular rate
- R_MAG = 0.0025f + sq(0.05f*dAngIMU.length()/dtIMU);
-
- // Calculate observation jacobians
- SH_MAG[0] = 2*magD*q3 + 2*magE*q2 + 2*magN*q1;
- SH_MAG[1] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
- SH_MAG[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
- SH_MAG[3] = sq(q3);
- SH_MAG[4] = sq(q2);
- SH_MAG[5] = sq(q1);
- SH_MAG[6] = sq(q0);
- SH_MAG[7] = 2*magN*q0;
- SH_MAG[8] = 2*magE*q3;
-
- for (uint8_t i=0; i<=20; i++) H_MAG[i] = 0;
- H_MAG[0] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
- H_MAG[1] = SH_MAG[0];
- H_MAG[2] = 2*magE*q1 - 2*magD*q0 - 2*magN*q2;
- H_MAG[3] = SH_MAG[2];
- H_MAG[15] = SH_MAG[5] - SH_MAG[4] - SH_MAG[3] + SH_MAG[6];
- H_MAG[16] = 2*q0*q3 + 2*q1*q2;
- H_MAG[17] = 2*q1*q3 - 2*q0*q2;
- H_MAG[18] = 1.0f;
-
- // Calculate Kalman gain
- SK_MX[0] = 1/(P[18][18] + R_MAG + P[1][18]*SH_MAG[0] + P[3][18]*SH_MAG[2] - P[15][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) - (2*magD*q0 - 2*magE*q1 + 2*magN*q2)*(P[18][2] + P[1][2]*SH_MAG[0] + P[3][2]*SH_MAG[2] - P[15][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][2]*(2*q0*q3 + 2*q1*q2) - P[17][2]*(2*q0*q2 - 2*q1*q3) - P[2][2]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[18][0] + P[1][0]*SH_MAG[0] + P[3][0]*SH_MAG[2] - P[15][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][0]*(2*q0*q3 + 2*q1*q2) - P[17][0]*(2*q0*q2 - 2*q1*q3) - P[2][0]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[18][1] + P[1][1]*SH_MAG[0] + P[3][1]*SH_MAG[2] - P[15][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][1]*(2*q0*q3 + 2*q1*q2) - P[17][1]*(2*q0*q2 - 2*q1*q3) - P[2][1]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[18][3] + P[1][3]*SH_MAG[0] + P[3][3]*SH_MAG[2] - P[15][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][3]*(2*q0*q3 + 2*q1*q2) - P[17][3]*(2*q0*q2 - 2*q1*q3) - P[2][3]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[18][15] + P[1][15]*SH_MAG[0] + P[3][15]*SH_MAG[2] - P[15][15]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][15]*(2*q0*q3 + 2*q1*q2) - P[17][15]*(2*q0*q2 - 2*q1*q3) - P[2][15]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][18]*(2*q0*q3 + 2*q1*q2) - P[17][18]*(2*q0*q2 - 2*q1*q3) - P[2][18]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + (2*q0*q3 + 2*q1*q2)*(P[18][16] + P[1][16]*SH_MAG[0] + P[3][16]*SH_MAG[2] - P[15][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][16]*(2*q0*q3 + 2*q1*q2) - P[17][16]*(2*q0*q2 - 2*q1*q3) - P[2][16]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[18][17] + P[1][17]*SH_MAG[0] + P[3][17]*SH_MAG[2] - P[15][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][17]*(2*q0*q3 + 2*q1*q2) - P[17][17]*(2*q0*q2 - 2*q1*q3) - P[2][17]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
- SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6];
- SK_MX[2] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
- SK_MX[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
- SK_MX[4] = 2*q0*q2 - 2*q1*q3;
- SK_MX[5] = 2*q0*q3 + 2*q1*q2;
- Kfusion[0] = SK_MX[0]*(P[0][18] + P[0][1]*SH_MAG[0] + P[0][3]*SH_MAG[2] + P[0][0]*SK_MX[3] - P[0][2]*SK_MX[2] - P[0][15]*SK_MX[1] + P[0][16]*SK_MX[5] - P[0][17]*SK_MX[4]);
- Kfusion[1] = SK_MX[0]*(P[1][18] + P[1][1]*SH_MAG[0] + P[1][3]*SH_MAG[2] + P[1][0]*SK_MX[3] - P[1][2]*SK_MX[2] - P[1][15]*SK_MX[1] + P[1][16]*SK_MX[5] - P[1][17]*SK_MX[4]);
- Kfusion[2] = SK_MX[0]*(P[2][18] + P[2][1]*SH_MAG[0] + P[2][3]*SH_MAG[2] + P[2][0]*SK_MX[3] - P[2][2]*SK_MX[2] - P[2][15]*SK_MX[1] + P[2][16]*SK_MX[5] - P[2][17]*SK_MX[4]);
- Kfusion[3] = SK_MX[0]*(P[3][18] + P[3][1]*SH_MAG[0] + P[3][3]*SH_MAG[2] + P[3][0]*SK_MX[3] - P[3][2]*SK_MX[2] - P[3][15]*SK_MX[1] + P[3][16]*SK_MX[5] - P[3][17]*SK_MX[4]);
- Kfusion[4] = SK_MX[0]*(P[4][18] + P[4][1]*SH_MAG[0] + P[4][3]*SH_MAG[2] + P[4][0]*SK_MX[3] - P[4][2]*SK_MX[2] - P[4][15]*SK_MX[1] + P[4][16]*SK_MX[5] - P[4][17]*SK_MX[4]);
- Kfusion[5] = SK_MX[0]*(P[5][18] + P[5][1]*SH_MAG[0] + P[5][3]*SH_MAG[2] + P[5][0]*SK_MX[3] - P[5][2]*SK_MX[2] - P[5][15]*SK_MX[1] + P[5][16]*SK_MX[5] - P[5][17]*SK_MX[4]);
- Kfusion[6] = SK_MX[0]*(P[6][18] + P[6][1]*SH_MAG[0] + P[6][3]*SH_MAG[2] + P[6][0]*SK_MX[3] - P[6][2]*SK_MX[2] - P[6][15]*SK_MX[1] + P[6][16]*SK_MX[5] - P[6][17]*SK_MX[4]);
- Kfusion[7] = SK_MX[0]*(P[7][18] + P[7][1]*SH_MAG[0] + P[7][3]*SH_MAG[2] + P[7][0]*SK_MX[3] - P[7][2]*SK_MX[2] - P[7][15]*SK_MX[1] + P[7][16]*SK_MX[5] - P[7][17]*SK_MX[4]);
- Kfusion[8] = SK_MX[0]*(P[8][18] + P[8][1]*SH_MAG[0] + P[8][3]*SH_MAG[2] + P[8][0]*SK_MX[3] - P[8][2]*SK_MX[2] - P[8][15]*SK_MX[1] + P[8][16]*SK_MX[5] - P[8][17]*SK_MX[4]);
- Kfusion[9] = SK_MX[0]*(P[9][18] + P[9][1]*SH_MAG[0] + P[9][3]*SH_MAG[2] + P[9][0]*SK_MX[3] - P[9][2]*SK_MX[2] - P[9][15]*SK_MX[1] + P[9][16]*SK_MX[5] - P[9][17]*SK_MX[4]);
- Kfusion[10] = SK_MX[0]*(P[10][18] + P[10][1]*SH_MAG[0] + P[10][3]*SH_MAG[2] + P[10][0]*SK_MX[3] - P[10][2]*SK_MX[2] - P[10][15]*SK_MX[1] + P[10][16]*SK_MX[5] - P[10][17]*SK_MX[4]);
- Kfusion[11] = SK_MX[0]*(P[11][18] + P[11][1]*SH_MAG[0] + P[11][3]*SH_MAG[2] + P[11][0]*SK_MX[3] - P[11][2]*SK_MX[2] - P[11][15]*SK_MX[1] + P[11][16]*SK_MX[5] - P[11][17]*SK_MX[4]);
- Kfusion[12] = SK_MX[0]*(P[12][18] + P[12][1]*SH_MAG[0] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[3] - P[12][2]*SK_MX[2] - P[12][15]*SK_MX[1] + P[12][16]*SK_MX[5] - P[12][17]*SK_MX[4]);
- Kfusion[13] = SK_MX[0]*(P[13][18] + P[13][1]*SH_MAG[0] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[3] - P[13][2]*SK_MX[2] - P[13][15]*SK_MX[1] + P[13][16]*SK_MX[5] - P[13][17]*SK_MX[4]);
- Kfusion[14] = SK_MX[0]*(P[14][18] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][15]*SK_MX[1] + P[14][16]*SK_MX[5] - P[14][17]*SK_MX[4]);
- Kfusion[15] = SK_MX[0]*(P[15][18] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][15]*SK_MX[1] + P[15][16]*SK_MX[5] - P[15][17]*SK_MX[4]);
- Kfusion[16] = SK_MX[0]*(P[16][18] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][15]*SK_MX[1] + P[16][16]*SK_MX[5] - P[16][17]*SK_MX[4]);
- Kfusion[17] = SK_MX[0]*(P[17][18] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][15]*SK_MX[1] + P[17][16]*SK_MX[5] - P[17][17]*SK_MX[4]);
- Kfusion[18] = SK_MX[0]*(P[18][18] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][15]*SK_MX[1] + P[18][16]*SK_MX[5] - P[18][17]*SK_MX[4]);
- Kfusion[19] = SK_MX[0]*(P[19][18] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][15]*SK_MX[1] + P[19][16]*SK_MX[5] - P[19][17]*SK_MX[4]);
- Kfusion[20] = SK_MX[0]*(P[20][18] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][15]*SK_MX[1] + P[20][16]*SK_MX[5] - P[20][17]*SK_MX[4]);
- varInnovMag[0] = 1.0f/SK_MX[0];
- innovMag[0] = MagPred[0] - magData.x;
-
- // reset the observation index to 0 (we start by fusing the X
- // measurement)
- obsIndex = 0;
- }
- else if (obsIndex == 1) // we are now fusing the Y measurement
- {
- // Calculate observation jacobians
- for (unsigned int i=0; i<n_states; i++) H_MAG[i] = 0;
- H_MAG[0] = SH_MAG[2];
- H_MAG[1] = SH_MAG[1];
- H_MAG[2] = SH_MAG[0];
- H_MAG[3] = 2*magD*q2 - SH_MAG[8] - SH_MAG[7];
- H_MAG[15] = 2*q1*q2 - 2*q0*q3;
- H_MAG[16] = SH_MAG[4] - SH_MAG[3] - SH_MAG[5] + SH_MAG[6];
- H_MAG[17] = 2*q0*q1 + 2*q2*q3;
- H_MAG[19] = 1;
-
- // Calculate Kalman gain
- SK_MY[0] = 1/(P[19][19] + R_MAG + P[0][19]*SH_MAG[2] + P[1][19]*SH_MAG[1] + P[2][19]*SH_MAG[0] - P[16][19]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[19][15] + P[0][15]*SH_MAG[2] + P[1][15]*SH_MAG[1] + P[2][15]*SH_MAG[0] - P[16][15]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][15]*(2*q0*q3 - 2*q1*q2) + P[17][15]*(2*q0*q1 + 2*q2*q3) - P[3][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[19][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[16][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][17]*(2*q0*q3 - 2*q1*q2) + P[17][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[16][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][3]*(2*q0*q3 - 2*q1*q2) + P[17][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[15][19]*(2*q0*q3 - 2*q1*q2) + P[17][19]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[19][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[16][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][0]*(2*q0*q3 - 2*q1*q2) + P[17][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[19][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[16][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][1]*(2*q0*q3 - 2*q1*q2) + P[17][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[19][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[16][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][2]*(2*q0*q3 - 2*q1*q2) + P[17][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[16][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][16]*(2*q0*q3 - 2*q1*q2) + P[17][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
- SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6];
- SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
- SK_MY[3] = 2*q0*q3 - 2*q1*q2;
- SK_MY[4] = 2*q0*q1 + 2*q2*q3;
- Kfusion[0] = SK_MY[0]*(P[0][19] + P[0][0]*SH_MAG[2] + P[0][1]*SH_MAG[1] + P[0][2]*SH_MAG[0] - P[0][3]*SK_MY[2] - P[0][16]*SK_MY[1] - P[0][15]*SK_MY[3] + P[0][17]*SK_MY[4]);
- Kfusion[1] = SK_MY[0]*(P[1][19] + P[1][0]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[1][2]*SH_MAG[0] - P[1][3]*SK_MY[2] - P[1][16]*SK_MY[1] - P[1][15]*SK_MY[3] + P[1][17]*SK_MY[4]);
- Kfusion[2] = SK_MY[0]*(P[2][19] + P[2][0]*SH_MAG[2] + P[2][1]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[2][3]*SK_MY[2] - P[2][16]*SK_MY[1] - P[2][15]*SK_MY[3] + P[2][17]*SK_MY[4]);
- Kfusion[3] = SK_MY[0]*(P[3][19] + P[3][0]*SH_MAG[2] + P[3][1]*SH_MAG[1] + P[3][2]*SH_MAG[0] - P[3][3]*SK_MY[2] - P[3][16]*SK_MY[1] - P[3][15]*SK_MY[3] + P[3][17]*SK_MY[4]);
- Kfusion[4] = SK_MY[0]*(P[4][19] + P[4][0]*SH_MAG[2] + P[4][1]*SH_MAG[1] + P[4][2]*SH_MAG[0] - P[4][3]*SK_MY[2] - P[4][16]*SK_MY[1] - P[4][15]*SK_MY[3] + P[4][17]*SK_MY[4]);
- Kfusion[5] = SK_MY[0]*(P[5][19] + P[5][0]*SH_MAG[2] + P[5][1]*SH_MAG[1] + P[5][2]*SH_MAG[0] - P[5][3]*SK_MY[2] - P[5][16]*SK_MY[1] - P[5][15]*SK_MY[3] + P[5][17]*SK_MY[4]);
- Kfusion[6] = SK_MY[0]*(P[6][19] + P[6][0]*SH_MAG[2] + P[6][1]*SH_MAG[1] + P[6][2]*SH_MAG[0] - P[6][3]*SK_MY[2] - P[6][16]*SK_MY[1] - P[6][15]*SK_MY[3] + P[6][17]*SK_MY[4]);
- Kfusion[7] = SK_MY[0]*(P[7][19] + P[7][0]*SH_MAG[2] + P[7][1]*SH_MAG[1] + P[7][2]*SH_MAG[0] - P[7][3]*SK_MY[2] - P[7][16]*SK_MY[1] - P[7][15]*SK_MY[3] + P[7][17]*SK_MY[4]);
- Kfusion[8] = SK_MY[0]*(P[8][19] + P[8][0]*SH_MAG[2] + P[8][1]*SH_MAG[1] + P[8][2]*SH_MAG[0] - P[8][3]*SK_MY[2] - P[8][16]*SK_MY[1] - P[8][15]*SK_MY[3] + P[8][17]*SK_MY[4]);
- Kfusion[9] = SK_MY[0]*(P[9][19] + P[9][0]*SH_MAG[2] + P[9][1]*SH_MAG[1] + P[9][2]*SH_MAG[0] - P[9][3]*SK_MY[2] - P[9][16]*SK_MY[1] - P[9][15]*SK_MY[3] + P[9][17]*SK_MY[4]);
- Kfusion[10] = SK_MY[0]*(P[10][19] + P[10][0]*SH_MAG[2] + P[10][1]*SH_MAG[1] + P[10][2]*SH_MAG[0] - P[10][3]*SK_MY[2] - P[10][16]*SK_MY[1] - P[10][15]*SK_MY[3] + P[10][17]*SK_MY[4]);
- Kfusion[11] = SK_MY[0]*(P[11][19] + P[11][0]*SH_MAG[2] + P[11][1]*SH_MAG[1] + P[11][2]*SH_MAG[0] - P[11][3]*SK_MY[2] - P[11][16]*SK_MY[1] - P[11][15]*SK_MY[3] + P[11][17]*SK_MY[4]);
- Kfusion[12] = SK_MY[0]*(P[12][19] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][16]*SK_MY[1] - P[12][15]*SK_MY[3] + P[12][17]*SK_MY[4]);
- Kfusion[13] = SK_MY[0]*(P[13][19] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][16]*SK_MY[1] - P[13][15]*SK_MY[3] + P[13][17]*SK_MY[4]);
- Kfusion[14] = SK_MY[0]*(P[14][19] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][16]*SK_MY[1] - P[14][15]*SK_MY[3] + P[14][17]*SK_MY[4]);
- Kfusion[15] = SK_MY[0]*(P[15][19] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][16]*SK_MY[1] - P[15][15]*SK_MY[3] + P[15][17]*SK_MY[4]);
- Kfusion[16] = SK_MY[0]*(P[16][19] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][16]*SK_MY[1] - P[16][15]*SK_MY[3] + P[16][17]*SK_MY[4]);
- Kfusion[17] = SK_MY[0]*(P[17][19] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][16]*SK_MY[1] - P[17][15]*SK_MY[3] + P[17][17]*SK_MY[4]);
- Kfusion[18] = SK_MY[0]*(P[18][19] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][16]*SK_MY[1] - P[18][15]*SK_MY[3] + P[18][17]*SK_MY[4]);
- Kfusion[19] = SK_MY[0]*(P[19][19] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][16]*SK_MY[1] - P[19][15]*SK_MY[3] + P[19][17]*SK_MY[4]);
- Kfusion[20] = SK_MY[0]*(P[20][19] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][16]*SK_MY[1] - P[20][15]*SK_MY[3] + P[20][17]*SK_MY[4]);
- varInnovMag[1] = 1.0f/SK_MY[0];
- innovMag[1] = MagPred[1] - magData.y;
- }
- else if (obsIndex == 2) // we are now fusing the Z measurement
- {
- // Calculate observation jacobians
- for (uint8_t i=0; i<=20; i++) H_MAG[i] = 0;
- H_MAG[0] = SH_MAG[1];
- H_MAG[1] = 2*magN*q3 - 2*magE*q0 - 2*magD*q1;
- H_MAG[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
- H_MAG[3] = SH_MAG[0];
- H_MAG[15] = 2*q0*q2 + 2*q1*q3;
- H_MAG[16] = 2*q2*q3 - 2*q0*q1;
- H_MAG[17] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
- H_MAG[20] = 1;
-
- // Calculate Kalman gain
- SK_MZ[0] = 1/(P[20][20] + R_MAG + P[0][20]*SH_MAG[1] + P[3][20]*SH_MAG[0] + P[17][20]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) - (2*magD*q1 + 2*magE*q0 - 2*magN*q3)*(P[20][1] + P[0][1]*SH_MAG[1] + P[3][1]*SH_MAG[0] + P[17][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][1]*(2*q0*q2 + 2*q1*q3) - P[16][1]*(2*q0*q1 - 2*q2*q3) - P[1][1]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][2] + P[0][2]*SH_MAG[1] + P[3][2]*SH_MAG[0] + P[17][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][2]*(2*q0*q2 + 2*q1*q3) - P[16][2]*(2*q0*q1 - 2*q2*q3) - P[1][2]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][0] + P[0][0]*SH_MAG[1] + P[3][0]*SH_MAG[0] + P[17][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][0]*(2*q0*q2 + 2*q1*q3) - P[16][0]*(2*q0*q1 - 2*q2*q3) - P[1][0]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][3] + P[0][3]*SH_MAG[1] + P[3][3]*SH_MAG[0] + P[17][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][3]*(2*q0*q2 + 2*q1*q3) - P[16][3]*(2*q0*q1 - 2*q2*q3) - P[1][3]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[1] + P[3][17]*SH_MAG[0] + P[17][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][17]*(2*q0*q2 + 2*q1*q3) - P[16][17]*(2*q0*q1 - 2*q2*q3) - P[1][17]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[15][20]*(2*q0*q2 + 2*q1*q3) - P[16][20]*(2*q0*q1 - 2*q2*q3) - P[1][20]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + (2*q0*q2 + 2*q1*q3)*(P[20][15] + P[0][15]*SH_MAG[1] + P[3][15]*SH_MAG[0] + P[17][15]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][15]*(2*q0*q2 + 2*q1*q3) - P[16][15]*(2*q0*q1 - 2*q2*q3) - P[1][15]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[20][16] + P[0][16]*SH_MAG[1] + P[3][16]*SH_MAG[0] + P[17][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][16]*(2*q0*q2 + 2*q1*q3) - P[16][16]*(2*q0*q1 - 2*q2*q3) - P[1][16]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
- SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
- SK_MZ[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
- SK_MZ[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
- SK_MZ[4] = 2*q0*q1 - 2*q2*q3;
- SK_MZ[5] = 2*q0*q2 + 2*q1*q3;
- Kfusion[0] = SK_MZ[0]*(P[0][20] + P[0][0]*SH_MAG[1] + P[0][3]*SH_MAG[0] - P[0][1]*SK_MZ[2] + P[0][2]*SK_MZ[3] + P[0][17]*SK_MZ[1] + P[0][15]*SK_MZ[5] - P[0][16]*SK_MZ[4]);
- Kfusion[1] = SK_MZ[0]*(P[1][20] + P[1][0]*SH_MAG[1] + P[1][3]*SH_MAG[0] - P[1][1]*SK_MZ[2] + P[1][2]*SK_MZ[3] + P[1][17]*SK_MZ[1] + P[1][15]*SK_MZ[5] - P[1][16]*SK_MZ[4]);
- Kfusion[2] = SK_MZ[0]*(P[2][20] + P[2][0]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[2][1]*SK_MZ[2] + P[2][2]*SK_MZ[3] + P[2][17]*SK_MZ[1] + P[2][15]*SK_MZ[5] - P[2][16]*SK_MZ[4]);
- Kfusion[3] = SK_MZ[0]*(P[3][20] + P[3][0]*SH_MAG[1] + P[3][3]*SH_MAG[0] - P[3][1]*SK_MZ[2] + P[3][2]*SK_MZ[3] + P[3][17]*SK_MZ[1] + P[3][15]*SK_MZ[5] - P[3][16]*SK_MZ[4]);
- Kfusion[4] = SK_MZ[0]*(P[4][20] + P[4][0]*SH_MAG[1] + P[4][3]*SH_MAG[0] - P[4][1]*SK_MZ[2] + P[4][2]*SK_MZ[3] + P[4][17]*SK_MZ[1] + P[4][15]*SK_MZ[5] - P[4][16]*SK_MZ[4]);
- Kfusion[5] = SK_MZ[0]*(P[5][20] + P[5][0]*SH_MAG[1] + P[5][3]*SH_MAG[0] - P[5][1]*SK_MZ[2] + P[5][2]*SK_MZ[3] + P[5][17]*SK_MZ[1] + P[5][15]*SK_MZ[5] - P[5][16]*SK_MZ[4]);
- Kfusion[6] = SK_MZ[0]*(P[6][20] + P[6][0]*SH_MAG[1] + P[6][3]*SH_MAG[0] - P[6][1]*SK_MZ[2] + P[6][2]*SK_MZ[3] + P[6][17]*SK_MZ[1] + P[6][15]*SK_MZ[5] - P[6][16]*SK_MZ[4]);
- Kfusion[7] = SK_MZ[0]*(P[7][20] + P[7][0]*SH_MAG[1] + P[7][3]*SH_MAG[0] - P[7][1]*SK_MZ[2] + P[7][2]*SK_MZ[3] + P[7][17]*SK_MZ[1] + P[7][15]*SK_MZ[5] - P[7][16]*SK_MZ[4]);
- Kfusion[8] = SK_MZ[0]*(P[8][20] + P[8][0]*SH_MAG[1] + P[8][3]*SH_MAG[0] - P[8][1]*SK_MZ[2] + P[8][2]*SK_MZ[3] + P[8][17]*SK_MZ[1] + P[8][15]*SK_MZ[5] - P[8][16]*SK_MZ[4]);
- Kfusion[9] = SK_MZ[0]*(P[9][20] + P[9][0]*SH_MAG[1] + P[9][3]*SH_MAG[0] - P[9][1]*SK_MZ[2] + P[9][2]*SK_MZ[3] + P[9][17]*SK_MZ[1] + P[9][15]*SK_MZ[5] - P[9][16]*SK_MZ[4]);
- Kfusion[10] = SK_MZ[0]*(P[10][20] + P[10][0]*SH_MAG[1] + P[10][3]*SH_MAG[0] - P[10][1]*SK_MZ[2] + P[10][2]*SK_MZ[3] + P[10][17]*SK_MZ[1] + P[10][15]*SK_MZ[5] - P[10][16]*SK_MZ[4]);
- Kfusion[11] = SK_MZ[0]*(P[11][20] + P[11][0]*SH_MAG[1] + P[11][3]*SH_MAG[0] - P[11][1]*SK_MZ[2] + P[11][2]*SK_MZ[3] + P[11][17]*SK_MZ[1] + P[11][15]*SK_MZ[5] - P[11][16]*SK_MZ[4]);
- Kfusion[12] = SK_MZ[0]*(P[12][20] + P[12][0]*SH_MAG[1] + P[12][3]*SH_MAG[0] - P[12][1]*SK_MZ[2] + P[12][2]*SK_MZ[3] + P[12][17]*SK_MZ[1] + P[12][15]*SK_MZ[5] - P[12][16]*SK_MZ[4]);
- Kfusion[13] = SK_MZ[0]*(P[13][20] + P[13][0]*SH_MAG[1] + P[13][3]*SH_MAG[0] - P[13][1]*SK_MZ[2] + P[13][2]*SK_MZ[3] + P[13][17]*SK_MZ[1] + P[13][15]*SK_MZ[5] - P[13][16]*SK_MZ[4]);
- Kfusion[14] = SK_MZ[0]*(P[14][20] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][17]*SK_MZ[1] + P[14][15]*SK_MZ[5] - P[14][16]*SK_MZ[4]);
- Kfusion[15] = SK_MZ[0]*(P[15][20] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][17]*SK_MZ[1] + P[15][15]*SK_MZ[5] - P[15][16]*SK_MZ[4]);
- Kfusion[16] = SK_MZ[0]*(P[16][20] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][17]*SK_MZ[1] + P[16][15]*SK_MZ[5] - P[16][16]*SK_MZ[4]);
- Kfusion[17] = SK_MZ[0]*(P[17][20] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][17]*SK_MZ[1] + P[17][15]*SK_MZ[5] - P[17][16]*SK_MZ[4]);
- Kfusion[18] = SK_MZ[0]*(P[18][20] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][17]*SK_MZ[1] + P[18][15]*SK_MZ[5] - P[18][16]*SK_MZ[4]);
- Kfusion[19] = SK_MZ[0]*(P[19][20] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][17]*SK_MZ[1] + P[19][15]*SK_MZ[5] - P[19][16]*SK_MZ[4]);
- Kfusion[20] = SK_MZ[0]*(P[20][20] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][17]*SK_MZ[1] + P[20][15]*SK_MZ[5] - P[20][16]*SK_MZ[4]);
- varInnovMag[2] = 1.0f/SK_MZ[0];
- innovMag[2] = MagPred[2] - magData.z;
-
- }
-
- // Check the innovation for consistency and don't fuse if > 5Sigma
- if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0)
- {
- // correct the state vector
- for (uint8_t j= 0; j<=indexLimit; j++)
- {
- states[j] = states[j] - Kfusion[j] * innovMag[obsIndex];
- }
- // normalise the quaternion states
- float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
- if (quatMag > 1e-12)
- {
- for (uint8_t j= 0; j<=3; j++)
- {
- float quatMagInv = 1.0f/quatMag;
- states[j] = states[j] * quatMagInv;
- }
- }
- // correct the covariance P = (I - K*H)*P
- // take advantage of the empty columns in KH to reduce the
- // number of operations
- for (uint8_t i = 0; i<=indexLimit; i++)
- {
- for (uint8_t j = 0; j<=3; j++)
- {
- KH[i][j] = Kfusion[i] * H_MAG[j];
- }
- for (uint8_t j = 4; j<=17; j++) KH[i][j] = 0.0f;
- if (!onGround)
- {
- for (uint8_t j = 15; j<=20; j++)
- {
- KH[i][j] = Kfusion[i] * H_MAG[j];
- }
- }
- else
- {
- for (uint8_t j = 15; j<=20; j++)
- {
- KH[i][j] = 0.0f;
- }
- }
- }
- for (uint8_t i = 0; i<=indexLimit; i++)
- {
- for (uint8_t j = 0; j<=indexLimit; j++)
- {
- KHP[i][j] = 0.0f;
- for (uint8_t k = 0; k<=3; k++)
- {
- KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
- }
- if (!onGround)
- {
- for (uint8_t k = 15; k<=20; k++)
- {
- KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
- }
- }
- }
- }
- }
- for (uint8_t i = 0; i<=indexLimit; i++)
- {
- for (uint8_t j = 0; j<=indexLimit; j++)
- {
- P[i][j] = P[i][j] - KHP[i][j];
- }
- }
- }
- obsIndex = obsIndex + 1;
-
- ForceSymmetry();
- ConstrainVariances();
-}
-
-void AttPosEKF::FuseAirspeed()
-{
- float vn;
- float ve;
- float vd;
- float vwn;
- float vwe;
- const float R_TAS = 2.0f;
- float SH_TAS[3];
- float Kfusion[21];
- float VtasPred;
-
- // Copy required states to local variable names
- vn = statesAtVtasMeasTime[4];
- ve = statesAtVtasMeasTime[5];
- vd = statesAtVtasMeasTime[6];
- vwn = statesAtVtasMeasTime[13];
- vwe = statesAtVtasMeasTime[14];
-
- // Need to check that it is flying before fusing airspeed data
- // Calculate the predicted airspeed
- VtasPred = sqrtf((ve - vwe)*(ve - vwe) + (vn - vwn)*(vn - vwn) + vd*vd);
- // Perform fusion of True Airspeed measurement
- if (useAirspeed && fuseVtasData && (VtasPred > 1.0f) && (VtasMeas > 8.0f))
- {
- // Calculate observation jacobians
- SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
- SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2*vwe))/2.0f;
- SH_TAS[2] = (SH_TAS[0]*(2.0f*vn - 2*vwn))/2.0f;
-
- float H_TAS[21];
- for (uint8_t i=0; i<=20; i++) H_TAS[i] = 0.0f;
- H_TAS[4] = SH_TAS[2];
- H_TAS[5] = SH_TAS[1];
- H_TAS[6] = vd*SH_TAS[0];
- H_TAS[13] = -SH_TAS[2];
- H_TAS[14] = -SH_TAS[1];
-
- // Calculate Kalman gains
- float SK_TAS = 1.0f/(R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[13][4]*SH_TAS[2] - P[14][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[13][5]*SH_TAS[2] - P[14][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][13]*SH_TAS[2] + P[5][13]*SH_TAS[1] - P[13][13]*SH_TAS[2] - P[14][13]*SH_TAS[1] + P[6][13]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][14]*SH_TAS[2] + P[5][14]*SH_TAS[1] - P[13][14]*SH_TAS[2] - P[14][14]*SH_TAS[1] + P[6][14]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[13][6]*SH_TAS[2] - P[14][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
- Kfusion[0] = SK_TAS*(P[0][4]*SH_TAS[2] - P[0][13]*SH_TAS[2] + P[0][5]*SH_TAS[1] - P[0][14]*SH_TAS[1] + P[0][6]*vd*SH_TAS[0]);
- Kfusion[1] = SK_TAS*(P[1][4]*SH_TAS[2] - P[1][13]*SH_TAS[2] + P[1][5]*SH_TAS[1] - P[1][14]*SH_TAS[1] + P[1][6]*vd*SH_TAS[0]);
- Kfusion[2] = SK_TAS*(P[2][4]*SH_TAS[2] - P[2][13]*SH_TAS[2] + P[2][5]*SH_TAS[1] - P[2][14]*SH_TAS[1] + P[2][6]*vd*SH_TAS[0]);
- Kfusion[3] = SK_TAS*(P[3][4]*SH_TAS[2] - P[3][13]*SH_TAS[2] + P[3][5]*SH_TAS[1] - P[3][14]*SH_TAS[1] + P[3][6]*vd*SH_TAS[0]);
- Kfusion[4] = SK_TAS*(P[4][4]*SH_TAS[2] - P[4][13]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[4][14]*SH_TAS[1] + P[4][6]*vd*SH_TAS[0]);
- Kfusion[5] = SK_TAS*(P[5][4]*SH_TAS[2] - P[5][13]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[5][14]*SH_TAS[1] + P[5][6]*vd*SH_TAS[0]);
- Kfusion[6] = SK_TAS*(P[6][4]*SH_TAS[2] - P[6][13]*SH_TAS[2] + P[6][5]*SH_TAS[1] - P[6][14]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]);
- Kfusion[7] = SK_TAS*(P[7][4]*SH_TAS[2] - P[7][13]*SH_TAS[2] + P[7][5]*SH_TAS[1] - P[7][14]*SH_TAS[1] + P[7][6]*vd*SH_TAS[0]);
- Kfusion[8] = SK_TAS*(P[8][4]*SH_TAS[2] - P[8][13]*SH_TAS[2] + P[8][5]*SH_TAS[1] - P[8][14]*SH_TAS[1] + P[8][6]*vd*SH_TAS[0]);
- Kfusion[9] = SK_TAS*(P[9][4]*SH_TAS[2] - P[9][13]*SH_TAS[2] + P[9][5]*SH_TAS[1] - P[9][14]*SH_TAS[1] + P[9][6]*vd*SH_TAS[0]);
- Kfusion[10] = SK_TAS*(P[10][4]*SH_TAS[2] - P[10][13]*SH_TAS[2] + P[10][5]*SH_TAS[1] - P[10][14]*SH_TAS[1] + P[10][6]*vd*SH_TAS[0]);
- Kfusion[11] = SK_TAS*(P[11][4]*SH_TAS[2] - P[11][13]*SH_TAS[2] + P[11][5]*SH_TAS[1] - P[11][14]*SH_TAS[1] + P[11][6]*vd*SH_TAS[0]);
- Kfusion[12] = SK_TAS*(P[12][4]*SH_TAS[2] - P[12][13]*SH_TAS[2] + P[12][5]*SH_TAS[1] - P[12][14]*SH_TAS[1] + P[12][6]*vd*SH_TAS[0]);
- Kfusion[13] = SK_TAS*(P[13][4]*SH_TAS[2] - P[13][13]*SH_TAS[2] + P[13][5]*SH_TAS[1] - P[13][14]*SH_TAS[1] + P[13][6]*vd*SH_TAS[0]);
- Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][13]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][14]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
- Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][13]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][14]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
- Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][13]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][14]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
- Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][13]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][14]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
- Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][13]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][14]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
- Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][13]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][14]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
- Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][13]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][14]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
- varInnovVtas = 1.0f/SK_TAS;
-
- // Calculate the measurement innovation
- innovVtas = VtasPred - VtasMeas;
- // Check the innovation for consistency and don't fuse if > 5Sigma
- if ((innovVtas*innovVtas*SK_TAS) < 25.0)
- {
- // correct the state vector
- for (uint8_t j=0; j<=20; j++)
- {
- states[j] = states[j] - Kfusion[j] * innovVtas;
- }
- // normalise the quaternion states
- float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
- if (quatMag > 1e-12f)
- {
- for (uint8_t j= 0; j<=3; j++)
- {
- float quatMagInv = 1.0f/quatMag;
- states[j] = states[j] * quatMagInv;
- }
- }
- // correct the covariance P = (I - K*H)*P
- // take advantage of the empty columns in H to reduce the
- // number of operations
- for (uint8_t i = 0; i<=20; i++)
- {
- for (uint8_t j = 0; j<=3; j++) KH[i][j] = 0.0;
- for (uint8_t j = 4; j<=6; j++)
- {
- KH[i][j] = Kfusion[i] * H_TAS[j];
- }
- for (uint8_t j = 7; j<=12; j++) KH[i][j] = 0.0;
- for (uint8_t j = 13; j<=14; j++)
- {
- KH[i][j] = Kfusion[i] * H_TAS[j];
- }
- for (uint8_t j = 15; j<=20; j++) KH[i][j] = 0.0;
- }
- for (uint8_t i = 0; i<=20; i++)
- {
- for (uint8_t j = 0; j<=20; j++)
- {
- KHP[i][j] = 0.0;
- for (uint8_t k = 4; k<=6; k++)
- {
- KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
- }
- for (uint8_t k = 13; k<=14; k++)
- {
- KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
- }
- }
- }
- for (uint8_t i = 0; i<=20; i++)
- {
- for (uint8_t j = 0; j<=20; j++)
- {
- P[i][j] = P[i][j] - KHP[i][j];
- }
- }
- }
- }
-
- ForceSymmetry();
- ConstrainVariances();
-}
-
-void AttPosEKF::zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
-{
- uint8_t row;
- uint8_t col;
- for (row=first; row<=last; row++)
- {
- for (col=0; col<n_states; col++)
- {
- covMat[row][col] = 0.0;
- }
- }
-}
-
-void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
-{
- uint8_t row;
- uint8_t col;
- for (col=first; col<=last; col++)
- {
- for (row=0; row < n_states; row++)
- {
- covMat[row][col] = 0.0;
- }
- }
-}
-
-float AttPosEKF::sq(float valIn)
-{
- return valIn*valIn;
-}
-
-// Store states in a history array along with time stamp
-void AttPosEKF::StoreStates(uint64_t timestamp_ms)
-{
- for (unsigned i=0; i<n_states; i++)
- storedStates[i][storeIndex] = states[i];
- statetimeStamp[storeIndex] = timestamp_ms;
- storeIndex++;
- if (storeIndex == data_buffer_size)
- storeIndex = 0;
-}
-
-void AttPosEKF::ResetStoredStates()
-{
- // reset all stored states
- memset(&storedStates[0][0], 0, sizeof(storedStates));
- memset(&statetimeStamp[0], 0, sizeof(statetimeStamp));
-
- // reset store index to first
- storeIndex = 0;
-
- // overwrite all existing states
- for (unsigned i = 0; i < n_states; i++) {
- storedStates[i][storeIndex] = states[i];
- }
-
- statetimeStamp[storeIndex] = millis();
-
- // increment to next storage index
- storeIndex++;
-}
-
-// Output the state vector stored at the time that best matches that specified by msec
-int AttPosEKF::RecallStates(float statesForFusion[n_states], uint64_t msec)
-{
- int ret = 0;
-
- // int64_t bestTimeDelta = 200;
- // unsigned bestStoreIndex = 0;
- // for (unsigned storeIndex = 0; storeIndex < data_buffer_size; storeIndex++)
- // {
- // // The time delta can also end up as negative number,
- // // since we might compare future to past or past to future
- // // therefore cast to int64.
- // int64_t timeDelta = (int64_t)msec - (int64_t)statetimeStamp[storeIndex];
- // if (timeDelta < 0) {
- // timeDelta = -timeDelta;
- // }
-
- // if (timeDelta < bestTimeDelta)
- // {
- // bestStoreIndex = storeIndex;
- // bestTimeDelta = timeDelta;
- // }
- // }
- // if (bestTimeDelta < 200) // only output stored state if < 200 msec retrieval error
- // {
- // for (uint8_t i=0; i < n_states; i++) {
- // if (isfinite(storedStates[i][bestStoreIndex])) {
- // statesForFusion[i] = storedStates[i][bestStoreIndex];
- // } else if (isfinite(states[i])) {
- // statesForFusion[i] = states[i];
- // } else {
- // // There is not much we can do here, except reporting the error we just
- // // found.
- // ret++;
- // }
- // }
- // else // otherwise output current state
- // {
- for (uint8_t i=0; i < n_states; i++) {
- if (isfinite(states[i])) {
- statesForFusion[i] = states[i];
- } else {
- ret++;
- }
- }
- // }
-
- return ret;
-}
-
-void AttPosEKF::quat2Tnb(Mat3f &Tnb, const float (&quat)[4])
-{
- // Calculate the nav to body cosine matrix
- float q00 = sq(quat[0]);
- float q11 = sq(quat[1]);
- float q22 = sq(quat[2]);
- float q33 = sq(quat[3]);
- float q01 = quat[0]*quat[1];
- float q02 = quat[0]*quat[2];
- float q03 = quat[0]*quat[3];
- float q12 = quat[1]*quat[2];
- float q13 = quat[1]*quat[3];
- float q23 = quat[2]*quat[3];
-
- Tnb.x.x = q00 + q11 - q22 - q33;
- Tnb.y.y = q00 - q11 + q22 - q33;
- Tnb.z.z = q00 - q11 - q22 + q33;
- Tnb.y.x = 2*(q12 - q03);
- Tnb.z.x = 2*(q13 + q02);
- Tnb.x.y = 2*(q12 + q03);
- Tnb.z.y = 2*(q23 - q01);
- Tnb.x.z = 2*(q13 - q02);
- Tnb.y.z = 2*(q23 + q01);
-}
-
-void AttPosEKF::quat2Tbn(Mat3f &Tbn, const float (&quat)[4])
-{
- // Calculate the body to nav cosine matrix
- float q00 = sq(quat[0]);
- float q11 = sq(quat[1]);
- float q22 = sq(quat[2]);
- float q33 = sq(quat[3]);
- float q01 = quat[0]*quat[1];
- float q02 = quat[0]*quat[2];
- float q03 = quat[0]*quat[3];
- float q12 = quat[1]*quat[2];
- float q13 = quat[1]*quat[3];
- float q23 = quat[2]*quat[3];
-
- Tbn.x.x = q00 + q11 - q22 - q33;
- Tbn.y.y = q00 - q11 + q22 - q33;
- Tbn.z.z = q00 - q11 - q22 + q33;
- Tbn.x.y = 2*(q12 - q03);
- Tbn.x.z = 2*(q13 + q02);
- Tbn.y.x = 2*(q12 + q03);
- Tbn.y.z = 2*(q23 - q01);
- Tbn.z.x = 2*(q13 - q02);
- Tbn.z.y = 2*(q23 + q01);
-}
-
-void AttPosEKF::eul2quat(float (&quat)[4], const float (&eul)[3])
-{
- float u1 = cos(0.5f*eul[0]);
- float u2 = cos(0.5f*eul[1]);
- float u3 = cos(0.5f*eul[2]);
- float u4 = sin(0.5f*eul[0]);
- float u5 = sin(0.5f*eul[1]);
- float u6 = sin(0.5f*eul[2]);
- quat[0] = u1*u2*u3+u4*u5*u6;
- quat[1] = u4*u2*u3-u1*u5*u6;
- quat[2] = u1*u5*u3+u4*u2*u6;
- quat[3] = u1*u2*u6-u4*u5*u3;
-}
-
-void AttPosEKF::quat2eul(float (&y)[3], const float (&u)[4])
-{
- y[0] = atan2f((2.0f*(u[2]*u[3]+u[0]*u[1])) , (u[0]*u[0]-u[1]*u[1]-u[2]*u[2]+u[3]*u[3]));
- y[1] = -asinf(2.0f*(u[1]*u[3]-u[0]*u[2]));
- y[2] = atan2f((2.0f*(u[1]*u[2]+u[0]*u[3])) , (u[0]*u[0]+u[1]*u[1]-u[2]*u[2]-u[3]*u[3]));
-}
-
-void AttPosEKF::calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD)
-{
- velNED[0] = gpsGndSpd*cosf(gpsCourse);
- velNED[1] = gpsGndSpd*sinf(gpsCourse);
- velNED[2] = gpsVelD;
-}
-
-void AttPosEKF::calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
-{
- posNED[0] = earthRadius * (lat - latRef);
- posNED[1] = earthRadius * cos(latRef) * (lon - lonRef);
- posNED[2] = -(hgt - hgtRef);
-}
-
-void AttPosEKF::calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
-{
- lat = latRef + posNED[0] * earthRadiusInv;
- lon = lonRef + posNED[1] * earthRadiusInv / cos(latRef);
- hgt = hgtRef - posNED[2];
-}
-
-void AttPosEKF::OnGroundCheck()
-{
- onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
- if (staticMode) {
- staticMode = !(GPSstatus > GPS_FIX_2D);
- }
-}
-
-void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude)
-{
- //Define Earth rotation vector in the NED navigation frame
- omega.x = earthRate*cosf(latitude);
- omega.y = 0.0f;
- omega.z = -earthRate*sinf(latitude);
-}
-
-void AttPosEKF::CovarianceInit()
-{
- // Calculate the initial covariance matrix P
- P[0][0] = 0.25f * sq(1.0f*deg2rad);
- P[1][1] = 0.25f * sq(1.0f*deg2rad);
- P[2][2] = 0.25f * sq(1.0f*deg2rad);
- P[3][3] = 0.25f * sq(10.0f*deg2rad);
- P[4][4] = sq(0.7);
- P[5][5] = P[4][4];
- P[6][6] = sq(0.7);
- P[7][7] = sq(15.0);
- P[8][8] = P[7][7];
- P[9][9] = sq(5.0);
- P[10][10] = sq(0.1*deg2rad*dtIMU);
- P[11][11] = P[10][10];
- P[12][12] = P[10][10];
- P[13][13] = sq(8.0f);
- P[14][4] = P[13][13];
- P[15][15] = sq(0.02f);
- P[16][16] = P[15][15];
- P[17][17] = P[15][15];
- P[18][18] = sq(0.02f);
- P[19][19] = P[18][18];
- P[20][20] = P[18][18];
-}
-
-float AttPosEKF::ConstrainFloat(float val, float min, float max)
-{
- return (val > max) ? max : ((val < min) ? min : val);
-}
-
-void AttPosEKF::ConstrainVariances()
-{
- if (!numericalProtection) {
- return;
- }
-
- // State vector:
- // 0-3: quaternions (q0, q1, q2, q3)
- // 4-6: Velocity - m/sec (North, East, Down)
- // 7-9: Position - m (North, East, Down)
- // 10-12: Delta Angle bias - rad (X,Y,Z)
- // 13-14: Wind Vector - m/sec (North,East)
- // 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
- // 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
-
- // Constrain quaternion variances
- for (unsigned i = 0; i < 4; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
- }
-
- // Constrain velocitie variances
- for (unsigned i = 4; i < 7; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
- }
-
- // Constrain position variances
- for (unsigned i = 7; i < 10; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e6f);
- }
-
- // Angle bias variances
- for (unsigned i = 10; i < 13; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, sq(0.175f * dtIMU));
- }
-
- // Wind velocity variances
- for (unsigned i = 13; i < 15; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
- }
-
- // Earth magnetic field variances
- for (unsigned i = 15; i < 18; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
- }
-
- // Body magnetic field variances
- for (unsigned i = 18; i < 21; i++) {
- P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
- }
-
-}
-
-void AttPosEKF::ConstrainStates()
-{
- if (!numericalProtection) {
- return;
- }
-
- // State vector:
- // 0-3: quaternions (q0, q1, q2, q3)
- // 4-6: Velocity - m/sec (North, East, Down)
- // 7-9: Position - m (North, East, Down)
- // 10-12: Delta Angle bias - rad (X,Y,Z)
- // 13-14: Wind Vector - m/sec (North,East)
- // 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
- // 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
-
-
- // Constrain quaternion
- for (unsigned i = 0; i < 4; i++) {
- states[i] = ConstrainFloat(states[i], -1.0f, 1.0f);
- }
-
- // Constrain velocities to what GPS can do for us
- for (unsigned i = 4; i < 7; i++) {
- states[i] = ConstrainFloat(states[i], -5.0e2f, 5.0e2f);
- }
-
- // Constrain position to a reasonable vehicle range (in meters)
- for (unsigned i = 7; i < 9; i++) {
- states[i] = ConstrainFloat(states[i], -1.0e6f, 1.0e6f);
- }
-
- // Constrain altitude
- states[9] = ConstrainFloat(states[9], -4.0e4f, 1.0e4f);
-
- // Angle bias limit - set to 8 degrees / sec
- for (unsigned i = 10; i < 13; i++) {
- states[i] = ConstrainFloat(states[i], -0.12f * dtIMU, 0.12f * dtIMU);
- }
-
- // Wind velocity limits - assume 120 m/s max velocity
- for (unsigned i = 13; i < 15; i++) {
- states[i] = ConstrainFloat(states[i], -120.0f, 120.0f);
- }
-
- // Earth magnetic field limits (in Gauss)
- for (unsigned i = 15; i < 18; i++) {
- states[i] = ConstrainFloat(states[i], -1.0f, 1.0f);
- }
-
- // Body magnetic field variances (in Gauss).
- // the max offset should be in this range.
- for (unsigned i = 18; i < 21; i++) {
- states[i] = ConstrainFloat(states[i], -0.5f, 0.5f);
- }
-
-}
-
-void AttPosEKF::ForceSymmetry()
-{
- if (!numericalProtection) {
- return;
- }
-
- // Force symmetry on the covariance matrix to prevent ill-conditioning
- // of the matrix which would cause the filter to blow-up
- for (unsigned i = 1; i < n_states; i++)
- {
- for (uint8_t j = 0; j < i; j++)
- {
- P[i][j] = 0.5f * (P[i][j] + P[j][i]);
- P[j][i] = P[i][j];
- }
- }
-}
-
-bool AttPosEKF::FilterHealthy()
-{
- if (!statesInitialised) {
- return false;
- }
-
- // XXX Check state vector for NaNs and ill-conditioning
-
- // Check if any of the major inputs timed out
- if (current_ekf_state.posTimeout || current_ekf_state.velTimeout || current_ekf_state.hgtTimeout) {
- return false;
- }
-
- // Nothing fired, return ok.
- return true;
-}
-
-/**
- * Reset the filter position states
- *
- * This resets the position to the last GPS measurement
- * or to zero in case of static position.
- */
-void AttPosEKF::ResetPosition(void)
-{
- if (staticMode) {
- states[7] = 0;
- states[8] = 0;
- } else if (GPSstatus >= GPS_FIX_3D) {
-
- // reset the states from the GPS measurements
- states[7] = posNE[0];
- states[8] = posNE[1];
- }
-}
-
-/**
- * Reset the height state.
- *
- * This resets the height state with the last altitude measurements
- */
-void AttPosEKF::ResetHeight(void)
-{
- // write to the state vector
- states[9] = -hgtMea;
-}
-
-/**
- * Reset the velocity state.
- */
-void AttPosEKF::ResetVelocity(void)
-{
- if (staticMode) {
- states[4] = 0.0f;
- states[5] = 0.0f;
- states[6] = 0.0f;
- } else if (GPSstatus >= GPS_FIX_3D) {
-
- states[4] = velNED[0]; // north velocity from last reading
- states[5] = velNED[1]; // east velocity from last reading
- states[6] = velNED[2]; // down velocity from last reading
- }
-}
-
-
-void AttPosEKF::FillErrorReport(struct ekf_status_report *err)
-{
- for (int i = 0; i < n_states; i++)
- {
- err->states[i] = states[i];
- }
-
- err->velHealth = current_ekf_state.velHealth;
- err->posHealth = current_ekf_state.posHealth;
- err->hgtHealth = current_ekf_state.hgtHealth;
- err->velTimeout = current_ekf_state.velTimeout;
- err->posTimeout = current_ekf_state.posTimeout;
- err->hgtTimeout = current_ekf_state.hgtTimeout;
-}
-
-bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
- bool err = false;
-
- // check all states and covariance matrices
- for (unsigned i = 0; i < n_states; i++) {
- for (unsigned j = 0; j < n_states; j++) {
- if (!isfinite(KH[i][j])) {
-
- err_report->covarianceNaN = true;
- err = true;
- } // intermediate result used for covariance updates
- if (!isfinite(KHP[i][j])) {
-
- err_report->covarianceNaN = true;
- err = true;
- } // intermediate result used for covariance updates
- if (!isfinite(P[i][j])) {
-
- err_report->covarianceNaN = true;
- err = true;
- } // covariance matrix
- }
-
- if (!isfinite(Kfusion[i])) {
-
- err_report->kalmanGainsNaN = true;
- err = true;
- } // Kalman gains
-
- if (!isfinite(states[i])) {
-
- err_report->statesNaN = true;
- err = true;
- } // state matrix
- }
-
- if (err) {
- FillErrorReport(err_report);
- }
-
- return err;
-
-}
-
-/**
- * Check the filter inputs and bound its operational state
- *
- * This check will reset the filter states if required
- * due to a failure of consistency or timeout checks.
- * it should be run after the measurement data has been
- * updated, but before any of the fusion steps are
- * executed.
- */
-int AttPosEKF::CheckAndBound()
-{
-
- // Store the old filter state
- bool currStaticMode = staticMode;
-
- // Reset the filter if the states went NaN
- if (StatesNaN(&last_ekf_error)) {
-
- InitializeDynamic(velNED, magDeclination);
-
- return 1;
- }
-
- // Reset the filter if the IMU data is too old
- if (dtIMU > 0.2f) {
-
- ResetVelocity();
- ResetPosition();
- ResetHeight();
- ResetStoredStates();
-
- // that's all we can do here, return
- return 2;
- }
-
- // Check if we're on ground - this also sets static mode.
- OnGroundCheck();
-
- // Check if we switched between states
- if (currStaticMode != staticMode) {
- ResetVelocity();
- ResetPosition();
- ResetHeight();
- ResetStoredStates();
-
- return 3;
- }
-
- return 0;
-}
-
-void AttPosEKF::AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat)
-{
- float initialRoll, initialPitch;
- float cosRoll, sinRoll, cosPitch, sinPitch;
- float magX, magY;
- float initialHdg, cosHeading, sinHeading;
-
- initialRoll = atan2(-ay, -az);
- initialPitch = atan2(ax, -az);
-
- cosRoll = cosf(initialRoll);
- sinRoll = sinf(initialRoll);
- cosPitch = cosf(initialPitch);
- sinPitch = sinf(initialPitch);
-
- magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
-
- magY = my * cosRoll - mz * sinRoll;
-
- initialHdg = atan2f(-magY, magX);
- /* true heading is the mag heading minus declination */
- initialHdg += declination;
-
- cosRoll = cosf(initialRoll * 0.5f);
- sinRoll = sinf(initialRoll * 0.5f);
-
- cosPitch = cosf(initialPitch * 0.5f);
- sinPitch = sinf(initialPitch * 0.5f);
-
- cosHeading = cosf(initialHdg * 0.5f);
- sinHeading = sinf(initialHdg * 0.5f);
-
- initQuat[0] = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
- initQuat[1] = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
- initQuat[2] = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
- initQuat[3] = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
-}
-
-void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
-{
-
- // Clear the init flag
- statesInitialised = false;
-
- magDeclination = declination;
-
- ZeroVariables();
-
- // Calculate initial filter quaternion states from raw measurements
- float initQuat[4];
- Vector3f initMagXYZ;
- initMagXYZ = magData - magBias;
- AttitudeInit(accel.x, accel.y, accel.z, initMagXYZ.x, initMagXYZ.y, initMagXYZ.z, magDeclination, initQuat);
-
- // Calculate initial Tbn matrix and rotate Mag measurements into NED
- // to set initial NED magnetic field states
- Mat3f DCM;
- quat2Tbn(DCM, initQuat);
- Vector3f initMagNED;
- initMagXYZ = magData - magBias;
- initMagNED.x = DCM.x.x*initMagXYZ.x + DCM.x.y*initMagXYZ.y + DCM.x.z*initMagXYZ.z;
- initMagNED.y = DCM.y.x*initMagXYZ.x + DCM.y.y*initMagXYZ.y + DCM.y.z*initMagXYZ.z;
- initMagNED.z = DCM.z.x*initMagXYZ.x + DCM.z.y*initMagXYZ.y + DCM.z.z*initMagXYZ.z;
-
-
-
- // write to state vector
- for (uint8_t j=0; j<=3; j++) states[j] = initQuat[j]; // quaternions
- for (uint8_t j=0; j<=2; j++) states[j+4] = initvelNED[j]; // velocities
- for (uint8_t j=0; j<=7; j++) states[j+7] = 0.0f; // positiions, dAngBias, windVel
- states[15] = initMagNED.x; // Magnetic Field North
- states[16] = initMagNED.y; // Magnetic Field East
- states[17] = initMagNED.z; // Magnetic Field Down
- states[18] = magBias.x; // Magnetic Field Bias X
- states[19] = magBias.y; // Magnetic Field Bias Y
- states[20] = magBias.z; // Magnetic Field Bias Z
-
- statesInitialised = true;
-
- // initialise the covariance matrix
- CovarianceInit();
-
- //Define Earth rotation vector in the NED navigation frame
- calcEarthRateNED(earthRateNED, latRef);
-
- //Initialise summed variables used by covariance prediction
- summedDelAng.x = 0.0f;
- summedDelAng.y = 0.0f;
- summedDelAng.z = 0.0f;
- summedDelVel.x = 0.0f;
- summedDelVel.y = 0.0f;
- summedDelVel.z = 0.0f;
-}
-
-void AttPosEKF::InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination)
-{
- //store initial lat,long and height
- latRef = referenceLat;
- lonRef = referenceLon;
- hgtRef = referenceHgt;
-
- memset(&last_ekf_error, 0, sizeof(last_ekf_error));
-
- InitializeDynamic(initvelNED, declination);
-}
-
-void AttPosEKF::ZeroVariables()
-{
- // Do the data structure init
- for (unsigned i = 0; i < n_states; i++) {
- for (unsigned j = 0; j < n_states; j++) {
- KH[i][j] = 0.0f; // intermediate result used for covariance updates
- KHP[i][j] = 0.0f; // intermediate result used for covariance updates
- P[i][j] = 0.0f; // covariance matrix
- }
-
- Kfusion[i] = 0.0f; // Kalman gains
- states[i] = 0.0f; // state matrix
- }
-
- for (unsigned i = 0; i < data_buffer_size; i++) {
-
- for (unsigned j = 0; j < n_states; j++) {
- storedStates[j][i] = 0.0f;
- }
-
- statetimeStamp[i] = 0;
- }
-
- memset(&current_ekf_state, 0, sizeof(current_ekf_state));
-}
-
-void AttPosEKF::GetFilterState(struct ekf_status_report *state)
-{
- memcpy(state, &current_ekf_state, sizeof(state));
-}
-
-void AttPosEKF::GetLastErrorState(struct ekf_status_report *last_error)
-{
- memcpy(last_error, &last_ekf_error, sizeof(last_error));
-}
diff --git a/src/modules/ekf_att_pos_estimator/estimator_21states.h b/src/modules/ekf_att_pos_estimator/estimator_21states.h
deleted file mode 100644
index a19ff1995..000000000
--- a/src/modules/ekf_att_pos_estimator/estimator_21states.h
+++ /dev/null
@@ -1,247 +0,0 @@
-#pragma once
-
-#include "estimator_utilities.h"
-
-class AttPosEKF {
-
-public:
-
- AttPosEKF();
- ~AttPosEKF();
-
- /* ##############################################
- *
- * M A I N F I L T E R P A R A M E T E R S
- *
- * ########################################### */
-
- /*
- * parameters are defined here and initialised in
- * the InitialiseParameters() (which is just 20 lines down)
- */
-
- float covTimeStepMax; // maximum time allowed between covariance predictions
- float covDelAngMax; // maximum delta angle between covariance predictions
- float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
-
- float yawVarScale;
- float windVelSigma;
- float dAngBiasSigma;
- float dVelBiasSigma;
- float magEarthSigma;
- float magBodySigma;
- float gndHgtSigma;
-
- float vneSigma;
- float vdSigma;
- float posNeSigma;
- float posDSigma;
- float magMeasurementSigma;
- float airspeedMeasurementSigma;
-
- float gyroProcessNoise;
- float accelProcessNoise;
-
- float EAS2TAS; // ratio f true to equivalent airspeed
-
- void InitialiseParameters()
- {
- covTimeStepMax = 0.07f; // maximum time allowed between covariance predictions
- covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
- rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
- EAS2TAS = 1.0f;
-
- yawVarScale = 1.0f;
- windVelSigma = 0.1f;
- dAngBiasSigma = 5.0e-7f;
- dVelBiasSigma = 1e-4f;
- magEarthSigma = 3.0e-4f;
- magBodySigma = 3.0e-4f;
- gndHgtSigma = 0.02f; // assume 2% terrain gradient 1-sigma
-
- vneSigma = 0.2f;
- vdSigma = 0.3f;
- posNeSigma = 2.0f;
- posDSigma = 2.0f;
-
- magMeasurementSigma = 0.05;
- airspeedMeasurementSigma = 1.4f;
- gyroProcessNoise = 1.4544411e-2f;
- accelProcessNoise = 0.5f;
- }
-
- // Global variables
- float KH[n_states][n_states]; // intermediate result used for covariance updates
- float KHP[n_states][n_states]; // intermediate result used for covariance updates
- float P[n_states][n_states]; // covariance matrix
- float Kfusion[n_states]; // Kalman gains
- float states[n_states]; // state matrix
- float storedStates[n_states][data_buffer_size]; // state vectors stored for the last 50 time steps
- uint32_t statetimeStamp[data_buffer_size]; // time stamp for each state vector stored
-
- float statesAtVelTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
- float statesAtPosTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
- float statesAtHgtTime[n_states]; // States at the effective measurement time for the hgtMea measurement
- float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
- float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
-
- Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
- Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
- Vector3f summedDelAng; // summed delta angles about the xyz body axes corrected for errors (rad)
- Vector3f summedDelVel; // summed delta velocities along the XYZ body axes corrected for errors (m/s)
- float accNavMag; // magnitude of navigation accel (- used to adjust GPS obs variance (m/s^2)
- Vector3f earthRateNED; // earths angular rate vector in NED (rad/s)
- Vector3f angRate; // angular rate vector in XYZ body axes measured by the IMU (rad/s)
- Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
- Vector3f dVelIMU;
- Vector3f dAngIMU;
- float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec)
- uint8_t fusionModeGPS; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
- float innovVelPos[6]; // innovation output
- float varInnovVelPos[6]; // innovation variance output
-
- float velNED[3]; // North, East, Down velocity obs (m/s)
- float posNE[2]; // North, East position obs (m)
- float hgtMea; // measured height (m)
- float posNED[3]; // North, East Down position (m)
-
- float innovMag[3]; // innovation output
- float varInnovMag[3]; // innovation variance output
- Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
- float innovVtas; // innovation output
- float varInnovVtas; // innovation variance output
- float VtasMeas; // true airspeed measurement (m/s)
- float magDeclination;
- float latRef; // WGS-84 latitude of reference point (rad)
- float lonRef; // WGS-84 longitude of reference point (rad)
- float hgtRef; // WGS-84 height of reference point (m)
- Vector3f magBias; // states representing magnetometer bias vector in XYZ body axes
- uint8_t covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
-
- // GPS input data variables
- float gpsCourse;
- float gpsVelD;
- float gpsLat;
- float gpsLon;
- float gpsHgt;
- uint8_t GPSstatus;
-
- // Baro input
- float baroHgt;
-
- bool statesInitialised;
-
- bool fuseVelData; // this boolean causes the posNE and velNED obs to be fused
- bool fusePosData; // this boolean causes the posNE and velNED obs to be fused
- bool fuseHgtData; // this boolean causes the hgtMea obs to be fused
- bool fuseMagData; // boolean true when magnetometer data is to be fused
- bool fuseVtasData; // boolean true when airspeed data is to be fused
-
- bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
- bool staticMode; ///< boolean true if no position feedback is fused
- bool useAirspeed; ///< boolean true if airspeed data is being used
- bool useCompass; ///< boolean true if magnetometer data is being used
-
- struct ekf_status_report current_ekf_state;
- struct ekf_status_report last_ekf_error;
-
- bool numericalProtection;
-
- unsigned storeIndex;
-
-
-void UpdateStrapdownEquationsNED();
-
-void CovariancePrediction(float dt);
-
-void FuseVelposNED();
-
-void FuseMagnetometer();
-
-void FuseAirspeed();
-
-void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
-
-void zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
-
-void quatNorm(float (&quatOut)[4], const float quatIn[4]);
-
-// store staes along with system time stamp in msces
-void StoreStates(uint64_t timestamp_ms);
-
-/**
- * Recall the state vector.
- *
- * Recalls the vector stored at closest time to the one specified by msec
- *
- * @return zero on success, integer indicating the number of invalid states on failure.
- * Does only copy valid states, if the statesForFusion vector was initialized
- * correctly by the caller, the result can be safely used, but is a mixture
- * time-wise where valid states were updated and invalid remained at the old
- * value.
- */
-int RecallStates(float statesForFusion[n_states], uint64_t msec);
-
-void ResetStoredStates();
-
-void quat2Tbn(Mat3f &Tbn, const float (&quat)[4]);
-
-void calcEarthRateNED(Vector3f &omega, float latitude);
-
-static void eul2quat(float (&quat)[4], const float (&eul)[3]);
-
-static void quat2eul(float (&eul)[3], const float (&quat)[4]);
-
-static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
-
-static void calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
-
-static void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
-
-static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
-
-static float sq(float valIn);
-
-void OnGroundCheck();
-
-void CovarianceInit();
-
-void InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination);
-
-float ConstrainFloat(float val, float min, float max);
-
-void ConstrainVariances();
-
-void ConstrainStates();
-
-void ForceSymmetry();
-
-int CheckAndBound();
-
-void ResetPosition();
-
-void ResetVelocity();
-
-void ZeroVariables();
-
-void GetFilterState(struct ekf_status_report *state);
-
-void GetLastErrorState(struct ekf_status_report *last_error);
-
-bool StatesNaN(struct ekf_status_report *err_report);
-void FillErrorReport(struct ekf_status_report *err);
-
-void InitializeDynamic(float (&initvelNED)[3], float declination);
-
-protected:
-
-bool FilterHealthy();
-
-void ResetHeight(void);
-
-void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat);
-
-};
-
-uint32_t millis();
-
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
index c17e034ad..15d018ab6 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_22states.cpp
@@ -1,4 +1,4 @@
-#include "estimator_23states.h"
+#include "estimator_22states.h"
#include <string.h>
#include <stdio.h>
#include <stdarg.h>
@@ -14,9 +14,6 @@ AttPosEKF::AttPosEKF() :
covTimeStepMax(0.0f),
covDelAngMax(0.0f),
rngFinderPitch(0.0f),
- a1(0.0f),
- a2(0.0f),
- a3(0.0f),
yawVarScale(0.0f),
windVelSigma(0.0f),
dAngBiasSigma(0.0f),
@@ -71,10 +68,6 @@ AttPosEKF::AttPosEKF() :
dtVelPosFilt(0.01f),
dtHgtFilt(0.01f),
dtGpsFilt(0.1f),
- windSpdFiltNorth(0.0f),
- windSpdFiltEast(0.0f),
- windSpdFiltAltitude(0.0f),
- windSpdFiltClimb(0.0f),
fusionModeGPS(0),
innovVelPos{},
varInnovVelPos{},
@@ -87,7 +80,6 @@ AttPosEKF::AttPosEKF() :
innovMag{},
varInnovMag{},
magData{},
- losData{},
innovVtas(0.0f),
innovRng(0.0f),
innovOptFlow{},
@@ -102,6 +94,8 @@ AttPosEKF::AttPosEKF() :
refSet(false),
magBias(),
covSkipCount(0),
+ lastFixTime_ms(0),
+ globalTimeStamp_ms(0),
gpsLat(0.0),
gpsLon(-M_PI),
gpsHgt(0.0f),
@@ -123,6 +117,7 @@ AttPosEKF::AttPosEKF() :
onGround(true),
staticMode(true),
+ useGPS(false),
useAirspeed(true),
useCompass(true),
useRangeFinder(true),
@@ -133,7 +128,7 @@ AttPosEKF::AttPosEKF() :
current_ekf_state{},
last_ekf_error{},
numericalProtection(true),
- storeIndex(0),
+ storeIndex(0),
storedOmega{},
Popt{},
flowStates{},
@@ -152,6 +147,7 @@ AttPosEKF::AttPosEKF() :
minFlowRng(0.0f),
moCompR_LOS(0.0f)
{
+
memset(&last_ekf_error, 0, sizeof(last_ekf_error));
memset(&current_ekf_state, 0, sizeof(current_ekf_state));
ZeroVariables();
@@ -185,9 +181,12 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
correctedDelAng.x = dAngIMU.x - states[10];
correctedDelAng.y = dAngIMU.y - states[11];
correctedDelAng.z = dAngIMU.z - states[12];
- dVelIMU.x = dVelIMU.x;
- dVelIMU.y = dVelIMU.y;
- dVelIMU.z = dVelIMU.z - states[13];
+
+ Vector3f dVelIMURel;
+
+ dVelIMURel.x = dVelIMU.x;
+ dVelIMURel.y = dVelIMU.y;
+ dVelIMURel.z = dVelIMU.z - states[13];
delAngTotal.x += correctedDelAng.x;
delAngTotal.y += correctedDelAng.y;
@@ -267,9 +266,9 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
// transform body delta velocities to delta velocities in the nav frame
// * and + operators have been overloaded
//delVelNav = Tbn*dVelIMU + gravityNED*dtIMU;
- delVelNav.x = Tbn.x.x*dVelIMU.x + Tbn.x.y*dVelIMU.y + Tbn.x.z*dVelIMU.z + gravityNED.x*dtIMU;
- delVelNav.y = Tbn.y.x*dVelIMU.x + Tbn.y.y*dVelIMU.y + Tbn.y.z*dVelIMU.z + gravityNED.y*dtIMU;
- delVelNav.z = Tbn.z.x*dVelIMU.x + Tbn.z.y*dVelIMU.y + Tbn.z.z*dVelIMU.z + gravityNED.z*dtIMU;
+ delVelNav.x = Tbn.x.x*dVelIMURel.x + Tbn.x.y*dVelIMURel.y + Tbn.x.z*dVelIMURel.z + gravityNED.x*dtIMU;
+ delVelNav.y = Tbn.y.x*dVelIMURel.x + Tbn.y.y*dVelIMURel.y + Tbn.y.z*dVelIMURel.z + gravityNED.y*dtIMU;
+ delVelNav.z = Tbn.z.x*dVelIMURel.x + Tbn.z.y*dVelIMURel.y + Tbn.z.z*dVelIMURel.z + gravityNED.z*dtIMU;
// calculate the magnitude of the nav acceleration (required for GPS
// variance estimation)
@@ -344,14 +343,9 @@ void AttPosEKF::CovariancePrediction(float dt)
}
if (!inhibitMagStates) {
for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma;
- for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma;
- } else {
- for (uint8_t i=16; i<=21; i++) processNoise[i] = 0;
- }
- if (!inhibitGndState) {
- processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
+ for (uint8_t i=19; i < n_states; i++) processNoise[i] = dt * magBodySigma;
} else {
- processNoise[22] = 0;
+ for (uint8_t i=16; i < n_states; i++) processNoise[i] = 0;
}
// square all sigmas
@@ -451,7 +445,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[0][19] = P[0][19] + P[1][19]*SF[7] + P[2][19]*SF[9] + P[3][19]*SF[8] + P[10][19]*SF[11] + P[11][19]*SPP[7] + P[12][19]*SPP[6];
nextP[0][20] = P[0][20] + P[1][20]*SF[7] + P[2][20]*SF[9] + P[3][20]*SF[8] + P[10][20]*SF[11] + P[11][20]*SPP[7] + P[12][20]*SPP[6];
nextP[0][21] = P[0][21] + P[1][21]*SF[7] + P[2][21]*SF[9] + P[3][21]*SF[8] + P[10][21]*SF[11] + P[11][21]*SPP[7] + P[12][21]*SPP[6];
- nextP[0][22] = P[0][22] + P[1][22]*SF[7] + P[2][22]*SF[9] + P[3][22]*SF[8] + P[10][22]*SF[11] + P[11][22]*SPP[7] + P[12][22]*SPP[6];
nextP[1][0] = P[1][0] + SQ[8] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2 + SF[7]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[9]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) + SF[8]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SF[11]*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2) + SPP[7]*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2) + SPP[6]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2);
nextP[1][1] = P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] + daxCov*SQ[9] - (P[10][1]*q0)/2 + SF[6]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[5]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) + SF[9]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SPP[6]*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2) - SPP[7]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2) + (dayCov*sq(q3))/4 + (dazCov*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2))/2;
nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[8]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[6]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SF[11]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2) - SPP[6]*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2))/2;
@@ -474,7 +467,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[1][19] = P[1][19] + P[0][19]*SF[6] + P[2][19]*SF[5] + P[3][19]*SF[9] + P[11][19]*SPP[6] - P[12][19]*SPP[7] - (P[10][19]*q0)/2;
nextP[1][20] = P[1][20] + P[0][20]*SF[6] + P[2][20]*SF[5] + P[3][20]*SF[9] + P[11][20]*SPP[6] - P[12][20]*SPP[7] - (P[10][20]*q0)/2;
nextP[1][21] = P[1][21] + P[0][21]*SF[6] + P[2][21]*SF[5] + P[3][21]*SF[9] + P[11][21]*SPP[6] - P[12][21]*SPP[7] - (P[10][21]*q0)/2;
- nextP[1][22] = P[1][22] + P[0][22]*SF[6] + P[2][22]*SF[5] + P[3][22]*SF[9] + P[11][22]*SPP[6] - P[12][22]*SPP[7] - (P[10][22]*q0)/2;
nextP[2][0] = P[2][0] + SQ[7] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2 + SF[7]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[9]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) + SF[8]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SF[11]*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2) + SPP[7]*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2) + SPP[6]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2);
nextP[2][1] = P[2][1] + SQ[5] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2 + SF[6]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[5]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) + SF[9]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SPP[6]*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2) - SPP[7]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2) - (q0*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2))/2;
nextP[2][2] = P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] + dayCov*SQ[9] + (dazCov*SQ[10])/4 - (P[11][2]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[8]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[6]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SF[11]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2) - SPP[6]*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2) + (daxCov*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2))/2;
@@ -497,7 +489,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[2][19] = P[2][19] + P[0][19]*SF[4] + P[1][19]*SF[8] + P[3][19]*SF[6] + P[12][19]*SF[11] - P[10][19]*SPP[6] - (P[11][19]*q0)/2;
nextP[2][20] = P[2][20] + P[0][20]*SF[4] + P[1][20]*SF[8] + P[3][20]*SF[6] + P[12][20]*SF[11] - P[10][20]*SPP[6] - (P[11][20]*q0)/2;
nextP[2][21] = P[2][21] + P[0][21]*SF[4] + P[1][21]*SF[8] + P[3][21]*SF[6] + P[12][21]*SF[11] - P[10][21]*SPP[6] - (P[11][21]*q0)/2;
- nextP[2][22] = P[2][22] + P[0][22]*SF[4] + P[1][22]*SF[8] + P[3][22]*SF[6] + P[12][22]*SF[11] - P[10][22]*SPP[6] - (P[11][22]*q0)/2;
nextP[3][0] = P[3][0] + SQ[6] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2 + SF[7]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[9]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) + SF[8]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SF[11]*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2) + SPP[7]*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2) + SPP[6]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2);
nextP[3][1] = P[3][1] + SQ[4] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2 + SF[6]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[5]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) + SF[9]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SPP[6]*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2) - SPP[7]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2) - (q0*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2))/2;
nextP[3][2] = P[3][2] + SQ[3] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[8]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[6]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SF[11]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2) - SPP[6]*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2) - (q0*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2))/2;
@@ -520,7 +511,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[3][19] = P[3][19] + P[0][19]*SF[5] + P[1][19]*SF[4] + P[2][19]*SF[7] - P[11][19]*SF[11] + P[10][19]*SPP[7] - (P[12][19]*q0)/2;
nextP[3][20] = P[3][20] + P[0][20]*SF[5] + P[1][20]*SF[4] + P[2][20]*SF[7] - P[11][20]*SF[11] + P[10][20]*SPP[7] - (P[12][20]*q0)/2;
nextP[3][21] = P[3][21] + P[0][21]*SF[5] + P[1][21]*SF[4] + P[2][21]*SF[7] - P[11][21]*SF[11] + P[10][21]*SPP[7] - (P[12][21]*q0)/2;
- nextP[3][22] = P[3][22] + P[0][22]*SF[5] + P[1][22]*SF[4] + P[2][22]*SF[7] - P[11][22]*SF[11] + P[10][22]*SPP[7] - (P[12][22]*q0)/2;
nextP[4][0] = P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4] + SF[7]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[9]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) + SF[8]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SF[11]*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]) + SPP[7]*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]) + SPP[6]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]);
nextP[4][1] = P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4] + SF[6]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[5]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) + SF[9]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SPP[6]*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]) - SPP[7]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]) - (q0*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]))/2;
nextP[4][2] = P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4] + SF[4]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[8]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[6]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SF[11]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]) - SPP[6]*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]) - (q0*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]))/2;
@@ -543,7 +533,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[4][19] = P[4][19] + P[0][19]*SF[3] + P[1][19]*SF[1] + P[2][19]*SPP[0] - P[3][19]*SPP[2] - P[13][19]*SPP[4];
nextP[4][20] = P[4][20] + P[0][20]*SF[3] + P[1][20]*SF[1] + P[2][20]*SPP[0] - P[3][20]*SPP[2] - P[13][20]*SPP[4];
nextP[4][21] = P[4][21] + P[0][21]*SF[3] + P[1][21]*SF[1] + P[2][21]*SPP[0] - P[3][21]*SPP[2] - P[13][21]*SPP[4];
- nextP[4][22] = P[4][22] + P[0][22]*SF[3] + P[1][22]*SF[1] + P[2][22]*SPP[0] - P[3][22]*SPP[2] - P[13][22]*SPP[4];
nextP[5][0] = P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3] + SF[7]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[9]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) + SF[8]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SF[11]*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]) + SPP[7]*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]) + SPP[6]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]);
nextP[5][1] = P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3] + SF[6]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[5]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) + SF[9]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SPP[6]*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]) - SPP[7]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]) - (q0*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]))/2;
nextP[5][2] = P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3] + SF[4]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[8]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[6]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SF[11]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]) - SPP[6]*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]) - (q0*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]))/2;
@@ -566,7 +555,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[5][19] = P[5][19] + P[0][19]*SF[2] + P[2][19]*SF[1] + P[3][19]*SF[3] - P[1][19]*SPP[0] + P[13][19]*SPP[3];
nextP[5][20] = P[5][20] + P[0][20]*SF[2] + P[2][20]*SF[1] + P[3][20]*SF[3] - P[1][20]*SPP[0] + P[13][20]*SPP[3];
nextP[5][21] = P[5][21] + P[0][21]*SF[2] + P[2][21]*SF[1] + P[3][21]*SF[3] - P[1][21]*SPP[0] + P[13][21]*SPP[3];
- nextP[5][22] = P[5][22] + P[0][22]*SF[2] + P[2][22]*SF[1] + P[3][22]*SF[3] - P[1][22]*SPP[0] + P[13][22]*SPP[3];
nextP[6][0] = P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[7]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[9]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[8]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[11]*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[7]*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[6]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)));
nextP[6][1] = P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[6]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[5]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[9]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[6]*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[7]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - (q0*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))))/2;
nextP[6][2] = P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[4]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[8]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[6]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[11]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[6]*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - (q0*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))))/2;
@@ -589,7 +577,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[6][19] = P[6][19] + P[1][19]*SF[2] + P[3][19]*SF[1] + P[0][19]*SPP[0] - P[2][19]*SPP[1] - P[13][19]*SPP[5];
nextP[6][20] = P[6][20] + P[1][20]*SF[2] + P[3][20]*SF[1] + P[0][20]*SPP[0] - P[2][20]*SPP[1] - P[13][20]*SPP[5];
nextP[6][21] = P[6][21] + P[1][21]*SF[2] + P[3][21]*SF[1] + P[0][21]*SPP[0] - P[2][21]*SPP[1] - P[13][21]*SPP[5];
- nextP[6][22] = P[6][22] + P[1][22]*SF[2] + P[3][22]*SF[1] + P[0][22]*SPP[0] - P[2][22]*SPP[1] - P[13][22]*SPP[5];
nextP[7][0] = P[7][0] + P[4][0]*dt + SF[7]*(P[7][1] + P[4][1]*dt) + SF[9]*(P[7][2] + P[4][2]*dt) + SF[8]*(P[7][3] + P[4][3]*dt) + SF[11]*(P[7][10] + P[4][10]*dt) + SPP[7]*(P[7][11] + P[4][11]*dt) + SPP[6]*(P[7][12] + P[4][12]*dt);
nextP[7][1] = P[7][1] + P[4][1]*dt + SF[6]*(P[7][0] + P[4][0]*dt) + SF[5]*(P[7][2] + P[4][2]*dt) + SF[9]*(P[7][3] + P[4][3]*dt) + SPP[6]*(P[7][11] + P[4][11]*dt) - SPP[7]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][10] + P[4][10]*dt))/2;
nextP[7][2] = P[7][2] + P[4][2]*dt + SF[4]*(P[7][0] + P[4][0]*dt) + SF[8]*(P[7][1] + P[4][1]*dt) + SF[6]*(P[7][3] + P[4][3]*dt) + SF[11]*(P[7][12] + P[4][12]*dt) - SPP[6]*(P[7][10] + P[4][10]*dt) - (q0*(P[7][11] + P[4][11]*dt))/2;
@@ -612,7 +599,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[7][19] = P[7][19] + P[4][19]*dt;
nextP[7][20] = P[7][20] + P[4][20]*dt;
nextP[7][21] = P[7][21] + P[4][21]*dt;
- nextP[7][22] = P[7][22] + P[4][22]*dt;
nextP[8][0] = P[8][0] + P[5][0]*dt + SF[7]*(P[8][1] + P[5][1]*dt) + SF[9]*(P[8][2] + P[5][2]*dt) + SF[8]*(P[8][3] + P[5][3]*dt) + SF[11]*(P[8][10] + P[5][10]*dt) + SPP[7]*(P[8][11] + P[5][11]*dt) + SPP[6]*(P[8][12] + P[5][12]*dt);
nextP[8][1] = P[8][1] + P[5][1]*dt + SF[6]*(P[8][0] + P[5][0]*dt) + SF[5]*(P[8][2] + P[5][2]*dt) + SF[9]*(P[8][3] + P[5][3]*dt) + SPP[6]*(P[8][11] + P[5][11]*dt) - SPP[7]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][10] + P[5][10]*dt))/2;
nextP[8][2] = P[8][2] + P[5][2]*dt + SF[4]*(P[8][0] + P[5][0]*dt) + SF[8]*(P[8][1] + P[5][1]*dt) + SF[6]*(P[8][3] + P[5][3]*dt) + SF[11]*(P[8][12] + P[5][12]*dt) - SPP[6]*(P[8][10] + P[5][10]*dt) - (q0*(P[8][11] + P[5][11]*dt))/2;
@@ -635,7 +621,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[8][19] = P[8][19] + P[5][19]*dt;
nextP[8][20] = P[8][20] + P[5][20]*dt;
nextP[8][21] = P[8][21] + P[5][21]*dt;
- nextP[8][22] = P[8][22] + P[5][22]*dt;
nextP[9][0] = P[9][0] + P[6][0]*dt + SF[7]*(P[9][1] + P[6][1]*dt) + SF[9]*(P[9][2] + P[6][2]*dt) + SF[8]*(P[9][3] + P[6][3]*dt) + SF[11]*(P[9][10] + P[6][10]*dt) + SPP[7]*(P[9][11] + P[6][11]*dt) + SPP[6]*(P[9][12] + P[6][12]*dt);
nextP[9][1] = P[9][1] + P[6][1]*dt + SF[6]*(P[9][0] + P[6][0]*dt) + SF[5]*(P[9][2] + P[6][2]*dt) + SF[9]*(P[9][3] + P[6][3]*dt) + SPP[6]*(P[9][11] + P[6][11]*dt) - SPP[7]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][10] + P[6][10]*dt))/2;
nextP[9][2] = P[9][2] + P[6][2]*dt + SF[4]*(P[9][0] + P[6][0]*dt) + SF[8]*(P[9][1] + P[6][1]*dt) + SF[6]*(P[9][3] + P[6][3]*dt) + SF[11]*(P[9][12] + P[6][12]*dt) - SPP[6]*(P[9][10] + P[6][10]*dt) - (q0*(P[9][11] + P[6][11]*dt))/2;
@@ -658,7 +643,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[9][19] = P[9][19] + P[6][19]*dt;
nextP[9][20] = P[9][20] + P[6][20]*dt;
nextP[9][21] = P[9][21] + P[6][21]*dt;
- nextP[9][22] = P[9][22] + P[6][22]*dt;
nextP[10][0] = P[10][0] + P[10][1]*SF[7] + P[10][2]*SF[9] + P[10][3]*SF[8] + P[10][10]*SF[11] + P[10][11]*SPP[7] + P[10][12]*SPP[6];
nextP[10][1] = P[10][1] + P[10][0]*SF[6] + P[10][2]*SF[5] + P[10][3]*SF[9] + P[10][11]*SPP[6] - P[10][12]*SPP[7] - (P[10][10]*q0)/2;
nextP[10][2] = P[10][2] + P[10][0]*SF[4] + P[10][1]*SF[8] + P[10][3]*SF[6] + P[10][12]*SF[11] - P[10][10]*SPP[6] - (P[10][11]*q0)/2;
@@ -681,7 +665,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[10][19] = P[10][19];
nextP[10][20] = P[10][20];
nextP[10][21] = P[10][21];
- nextP[10][22] = P[10][22];
nextP[11][0] = P[11][0] + P[11][1]*SF[7] + P[11][2]*SF[9] + P[11][3]*SF[8] + P[11][10]*SF[11] + P[11][11]*SPP[7] + P[11][12]*SPP[6];
nextP[11][1] = P[11][1] + P[11][0]*SF[6] + P[11][2]*SF[5] + P[11][3]*SF[9] + P[11][11]*SPP[6] - P[11][12]*SPP[7] - (P[11][10]*q0)/2;
nextP[11][2] = P[11][2] + P[11][0]*SF[4] + P[11][1]*SF[8] + P[11][3]*SF[6] + P[11][12]*SF[11] - P[11][10]*SPP[6] - (P[11][11]*q0)/2;
@@ -704,7 +687,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[11][19] = P[11][19];
nextP[11][20] = P[11][20];
nextP[11][21] = P[11][21];
- nextP[11][22] = P[11][22];
nextP[12][0] = P[12][0] + P[12][1]*SF[7] + P[12][2]*SF[9] + P[12][3]*SF[8] + P[12][10]*SF[11] + P[12][11]*SPP[7] + P[12][12]*SPP[6];
nextP[12][1] = P[12][1] + P[12][0]*SF[6] + P[12][2]*SF[5] + P[12][3]*SF[9] + P[12][11]*SPP[6] - P[12][12]*SPP[7] - (P[12][10]*q0)/2;
nextP[12][2] = P[12][2] + P[12][0]*SF[4] + P[12][1]*SF[8] + P[12][3]*SF[6] + P[12][12]*SF[11] - P[12][10]*SPP[6] - (P[12][11]*q0)/2;
@@ -727,7 +709,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[12][19] = P[12][19];
nextP[12][20] = P[12][20];
nextP[12][21] = P[12][21];
- nextP[12][22] = P[12][22];
nextP[13][0] = P[13][0] + P[13][1]*SF[7] + P[13][2]*SF[9] + P[13][3]*SF[8] + P[13][10]*SF[11] + P[13][11]*SPP[7] + P[13][12]*SPP[6];
nextP[13][1] = P[13][1] + P[13][0]*SF[6] + P[13][2]*SF[5] + P[13][3]*SF[9] + P[13][11]*SPP[6] - P[13][12]*SPP[7] - (P[13][10]*q0)/2;
nextP[13][2] = P[13][2] + P[13][0]*SF[4] + P[13][1]*SF[8] + P[13][3]*SF[6] + P[13][12]*SF[11] - P[13][10]*SPP[6] - (P[13][11]*q0)/2;
@@ -750,7 +731,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[13][19] = P[13][19];
nextP[13][20] = P[13][20];
nextP[13][21] = P[13][21];
- nextP[13][22] = P[13][22];
nextP[14][0] = P[14][0] + P[14][1]*SF[7] + P[14][2]*SF[9] + P[14][3]*SF[8] + P[14][10]*SF[11] + P[14][11]*SPP[7] + P[14][12]*SPP[6];
nextP[14][1] = P[14][1] + P[14][0]*SF[6] + P[14][2]*SF[5] + P[14][3]*SF[9] + P[14][11]*SPP[6] - P[14][12]*SPP[7] - (P[14][10]*q0)/2;
nextP[14][2] = P[14][2] + P[14][0]*SF[4] + P[14][1]*SF[8] + P[14][3]*SF[6] + P[14][12]*SF[11] - P[14][10]*SPP[6] - (P[14][11]*q0)/2;
@@ -773,7 +753,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[14][19] = P[14][19];
nextP[14][20] = P[14][20];
nextP[14][21] = P[14][21];
- nextP[14][22] = P[14][22];
nextP[15][0] = P[15][0] + P[15][1]*SF[7] + P[15][2]*SF[9] + P[15][3]*SF[8] + P[15][10]*SF[11] + P[15][11]*SPP[7] + P[15][12]*SPP[6];
nextP[15][1] = P[15][1] + P[15][0]*SF[6] + P[15][2]*SF[5] + P[15][3]*SF[9] + P[15][11]*SPP[6] - P[15][12]*SPP[7] - (P[15][10]*q0)/2;
nextP[15][2] = P[15][2] + P[15][0]*SF[4] + P[15][1]*SF[8] + P[15][3]*SF[6] + P[15][12]*SF[11] - P[15][10]*SPP[6] - (P[15][11]*q0)/2;
@@ -796,7 +775,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[15][19] = P[15][19];
nextP[15][20] = P[15][20];
nextP[15][21] = P[15][21];
- nextP[15][22] = P[15][22];
nextP[16][0] = P[16][0] + P[16][1]*SF[7] + P[16][2]*SF[9] + P[16][3]*SF[8] + P[16][10]*SF[11] + P[16][11]*SPP[7] + P[16][12]*SPP[6];
nextP[16][1] = P[16][1] + P[16][0]*SF[6] + P[16][2]*SF[5] + P[16][3]*SF[9] + P[16][11]*SPP[6] - P[16][12]*SPP[7] - (P[16][10]*q0)/2;
nextP[16][2] = P[16][2] + P[16][0]*SF[4] + P[16][1]*SF[8] + P[16][3]*SF[6] + P[16][12]*SF[11] - P[16][10]*SPP[6] - (P[16][11]*q0)/2;
@@ -819,7 +797,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[16][19] = P[16][19];
nextP[16][20] = P[16][20];
nextP[16][21] = P[16][21];
- nextP[16][22] = P[16][22];
nextP[17][0] = P[17][0] + P[17][1]*SF[7] + P[17][2]*SF[9] + P[17][3]*SF[8] + P[17][10]*SF[11] + P[17][11]*SPP[7] + P[17][12]*SPP[6];
nextP[17][1] = P[17][1] + P[17][0]*SF[6] + P[17][2]*SF[5] + P[17][3]*SF[9] + P[17][11]*SPP[6] - P[17][12]*SPP[7] - (P[17][10]*q0)/2;
nextP[17][2] = P[17][2] + P[17][0]*SF[4] + P[17][1]*SF[8] + P[17][3]*SF[6] + P[17][12]*SF[11] - P[17][10]*SPP[6] - (P[17][11]*q0)/2;
@@ -842,7 +819,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[17][19] = P[17][19];
nextP[17][20] = P[17][20];
nextP[17][21] = P[17][21];
- nextP[17][22] = P[17][22];
nextP[18][0] = P[18][0] + P[18][1]*SF[7] + P[18][2]*SF[9] + P[18][3]*SF[8] + P[18][10]*SF[11] + P[18][11]*SPP[7] + P[18][12]*SPP[6];
nextP[18][1] = P[18][1] + P[18][0]*SF[6] + P[18][2]*SF[5] + P[18][3]*SF[9] + P[18][11]*SPP[6] - P[18][12]*SPP[7] - (P[18][10]*q0)/2;
nextP[18][2] = P[18][2] + P[18][0]*SF[4] + P[18][1]*SF[8] + P[18][3]*SF[6] + P[18][12]*SF[11] - P[18][10]*SPP[6] - (P[18][11]*q0)/2;
@@ -865,7 +841,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[18][19] = P[18][19];
nextP[18][20] = P[18][20];
nextP[18][21] = P[18][21];
- nextP[18][22] = P[18][22];
nextP[19][0] = P[19][0] + P[19][1]*SF[7] + P[19][2]*SF[9] + P[19][3]*SF[8] + P[19][10]*SF[11] + P[19][11]*SPP[7] + P[19][12]*SPP[6];
nextP[19][1] = P[19][1] + P[19][0]*SF[6] + P[19][2]*SF[5] + P[19][3]*SF[9] + P[19][11]*SPP[6] - P[19][12]*SPP[7] - (P[19][10]*q0)/2;
nextP[19][2] = P[19][2] + P[19][0]*SF[4] + P[19][1]*SF[8] + P[19][3]*SF[6] + P[19][12]*SF[11] - P[19][10]*SPP[6] - (P[19][11]*q0)/2;
@@ -888,7 +863,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[19][19] = P[19][19];
nextP[19][20] = P[19][20];
nextP[19][21] = P[19][21];
- nextP[19][22] = P[19][22];
nextP[20][0] = P[20][0] + P[20][1]*SF[7] + P[20][2]*SF[9] + P[20][3]*SF[8] + P[20][10]*SF[11] + P[20][11]*SPP[7] + P[20][12]*SPP[6];
nextP[20][1] = P[20][1] + P[20][0]*SF[6] + P[20][2]*SF[5] + P[20][3]*SF[9] + P[20][11]*SPP[6] - P[20][12]*SPP[7] - (P[20][10]*q0)/2;
nextP[20][2] = P[20][2] + P[20][0]*SF[4] + P[20][1]*SF[8] + P[20][3]*SF[6] + P[20][12]*SF[11] - P[20][10]*SPP[6] - (P[20][11]*q0)/2;
@@ -911,7 +885,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[20][19] = P[20][19];
nextP[20][20] = P[20][20];
nextP[20][21] = P[20][21];
- nextP[20][22] = P[20][22];
nextP[21][0] = P[21][0] + P[21][1]*SF[7] + P[21][2]*SF[9] + P[21][3]*SF[8] + P[21][10]*SF[11] + P[21][11]*SPP[7] + P[21][12]*SPP[6];
nextP[21][1] = P[21][1] + P[21][0]*SF[6] + P[21][2]*SF[5] + P[21][3]*SF[9] + P[21][11]*SPP[6] - P[21][12]*SPP[7] - (P[21][10]*q0)/2;
nextP[21][2] = P[21][2] + P[21][0]*SF[4] + P[21][1]*SF[8] + P[21][3]*SF[6] + P[21][12]*SF[11] - P[21][10]*SPP[6] - (P[21][11]*q0)/2;
@@ -934,30 +907,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[21][19] = P[21][19];
nextP[21][20] = P[21][20];
nextP[21][21] = P[21][21];
- nextP[21][22] = P[21][22];
- nextP[22][0] = P[22][0] + P[22][1]*SF[7] + P[22][2]*SF[9] + P[22][3]*SF[8] + P[22][10]*SF[11] + P[22][11]*SPP[7] + P[22][12]*SPP[6];
- nextP[22][1] = P[22][1] + P[22][0]*SF[6] + P[22][2]*SF[5] + P[22][3]*SF[9] + P[22][11]*SPP[6] - P[22][12]*SPP[7] - (P[22][10]*q0)/2;
- nextP[22][2] = P[22][2] + P[22][0]*SF[4] + P[22][1]*SF[8] + P[22][3]*SF[6] + P[22][12]*SF[11] - P[22][10]*SPP[6] - (P[22][11]*q0)/2;
- nextP[22][3] = P[22][3] + P[22][0]*SF[5] + P[22][1]*SF[4] + P[22][2]*SF[7] - P[22][11]*SF[11] + P[22][10]*SPP[7] - (P[22][12]*q0)/2;
- nextP[22][4] = P[22][4] + P[22][1]*SF[1] + P[22][0]*SF[3] + P[22][2]*SPP[0] - P[22][3]*SPP[2] - P[22][13]*SPP[4];
- nextP[22][5] = P[22][5] + P[22][0]*SF[2] + P[22][2]*SF[1] + P[22][3]*SF[3] - P[22][1]*SPP[0] + P[22][13]*SPP[3];
- nextP[22][6] = P[22][6] + P[22][1]*SF[2] + P[22][3]*SF[1] + P[22][0]*SPP[0] - P[22][2]*SPP[1] - P[22][13]*SPP[5];
- nextP[22][7] = P[22][7] + P[22][4]*dt;
- nextP[22][8] = P[22][8] + P[22][5]*dt;
- nextP[22][9] = P[22][9] + P[22][6]*dt;
- nextP[22][10] = P[22][10];
- nextP[22][11] = P[22][11];
- nextP[22][12] = P[22][12];
- nextP[22][13] = P[22][13];
- nextP[22][14] = P[22][14];
- nextP[22][15] = P[22][15];
- nextP[22][16] = P[22][16];
- nextP[22][17] = P[22][17];
- nextP[22][18] = P[22][18];
- nextP[22][19] = P[22][19];
- nextP[22][20] = P[22][20];
- nextP[22][21] = P[22][21];
- nextP[22][22] = P[22][22];
for (unsigned i = 0; i < n_states; i++)
{
@@ -1031,7 +980,7 @@ void AttPosEKF::FuseVelposNED()
bool fuseData[6] = {false,false,false,false,false,false};
uint8_t stateIndex;
uint8_t obsIndex;
- uint8_t indexLimit = 22;
+ uint8_t indexLimit = 21;
// declare variables used by state and covariance update calculations
float velErr;
@@ -1230,15 +1179,11 @@ void AttPosEKF::FuseVelposNED()
}
// Don't update magnetic field states if inhibited
if (inhibitMagStates) {
- for (uint8_t i = 16; i<=21; i++)
+ for (uint8_t i = 16; i < n_states; i++)
{
Kfusion[i] = 0;
}
}
- // Don't update terrain state if inhibited
- if (inhibitGndState) {
- Kfusion[22] = 0;
- }
// Calculate state corrections and re-normalise the quaternions
for (uint8_t i = 0; i<=indexLimit; i++)
@@ -1415,15 +1360,10 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]);
Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]);
} else {
- for (uint8_t i=16; i <= 21; i++) {
+ for (uint8_t i=16; i < n_states; i++) {
Kfusion[i] = 0;
}
}
- if (!inhibitGndState) {
- Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
- } else {
- Kfusion[22] = 0;
- }
varInnovMag[0] = 1.0f/SK_MX[0];
innovMag[0] = MagPred[0] - magData.x;
}
@@ -1598,14 +1538,14 @@ void AttPosEKF::FuseMagnetometer()
for (uint8_t j = 4; j <= 15; j++) KH[i][j] = 0.0f;
if (!onGround)
{
- for (uint8_t j = 16; j <= 21; j++)
+ for (uint8_t j = 16; j < n_states; j++)
{
KH[i][j] = Kfusion[i] * H_MAG[j];
}
}
else
{
- for (uint8_t j = 16; j <= 21; j++)
+ for (uint8_t j = 16; j < n_states; j++)
{
KH[i][j] = 0.0f;
}
@@ -1622,7 +1562,7 @@ void AttPosEKF::FuseMagnetometer()
}
if (!onGround)
{
- for (uint8_t k = 16; k<=21; k++)
+ for (uint8_t k = 16; k < n_states; k++)
{
KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
}
@@ -1669,32 +1609,6 @@ void AttPosEKF::FuseAirspeed()
// Perform fusion of True Airspeed measurement
if (useAirspeed && fuseVtasData && (VtasPred > 1.0f) && (VtasMeas > 8.0f))
{
-
- float altDiff = fabsf(windSpdFiltAltitude - hgtMea);
-
- if (isfinite(windSpdFiltClimb)) {
- windSpdFiltClimb = ((1.0f - 0.0002f) * windSpdFiltClimb) + (0.0002f * states[6]);
- } else {
- windSpdFiltClimb = states[6];
- }
-
- if (altDiff < 20.0f) {
- // Lowpass the output of the wind estimate - we want a long-term
- // stable estimate, but not start to load into the overall dynamics
- // of the system (which adjusting covariances would do)
-
- // Change filter coefficient based on altitude change rate
- float windFiltCoeff = ConstrainFloat(fabsf(windSpdFiltClimb) / 1000.0f, 0.00005f, 0.2f);
-
- windSpdFiltNorth = ((1.0f - windFiltCoeff) * windSpdFiltNorth) + (windFiltCoeff * vwn);
- windSpdFiltEast = ((1.0f - windFiltCoeff) * windSpdFiltEast) + (windFiltCoeff * vwe);
- } else {
- windSpdFiltNorth = vwn;
- windSpdFiltEast = vwe;
- }
-
- windSpdFiltAltitude = hgtMea;
-
// Calculate observation jacobians
SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2*vwe))/2.0f;
@@ -1750,7 +1664,7 @@ void AttPosEKF::FuseAirspeed()
Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]);
} else {
- for (uint8_t i=16; i <= 21; i++) {
+ for (uint8_t i=16; i < n_states; i++) {
Kfusion[i] = 0;
}
}
@@ -1762,7 +1676,7 @@ void AttPosEKF::FuseAirspeed()
if ((innovVtas*innovVtas*SK_TAS) < 25.0f)
{
// correct the state vector
- for (uint8_t j=0; j <= 22; j++)
+ for (uint8_t j=0; j < n_states; j++)
{
states[j] = states[j] - Kfusion[j] * innovVtas;
}
@@ -1779,7 +1693,7 @@ void AttPosEKF::FuseAirspeed()
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in H to reduce the
// number of operations
- for (uint8_t i = 0; i <= 22; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
for (uint8_t j = 0; j <= 3; j++) KH[i][j] = 0.0;
for (uint8_t j = 4; j <= 6; j++)
@@ -1791,11 +1705,11 @@ void AttPosEKF::FuseAirspeed()
{
KH[i][j] = Kfusion[i] * H_TAS[j];
}
- for (uint8_t j = 16; j <= 22; j++) KH[i][j] = 0.0;
+ for (uint8_t j = 16; j < n_states; j++) KH[i][j] = 0.0;
}
- for (uint8_t i = 0; i <= 22; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j <= 22; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
KHP[i][j] = 0.0;
for (uint8_t k = 4; k <= 6; k++)
@@ -1808,9 +1722,9 @@ void AttPosEKF::FuseAirspeed()
}
}
}
- for (uint8_t i = 0; i <= 22; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j <= 22; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
P[i][j] = P[i][j] - KHP[i][j];
}
@@ -1835,356 +1749,269 @@ void AttPosEKF::zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uin
}
}
-void AttPosEKF::FuseRangeFinder()
+void AttPosEKF::FuseOptFlow()
{
-
- // Local variables
- float rngPred;
- float SH_RNG[5];
- float H_RNG[23];
- float SK_RNG[6];
- float cosRngTilt;
- const float R_RNG = 0.25f; // 0.5 m2 rangefinder measurement variance
-
- // Copy required states to local variable names
- float q0 = statesAtRngTime[0];
- float q1 = statesAtRngTime[1];
- float q2 = statesAtRngTime[2];
- float q3 = statesAtRngTime[3];
- float pd = statesAtRngTime[9];
- float ptd = statesAtRngTime[22];
-
- // Need to check that our range finder tilt angle is less than 30 degrees and we are using range finder data
- SH_RNG[4] = sinf(rngFinderPitch);
- cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cosf(rngFinderPitch);
- if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f)
+ static float SH_LOS[13];
+ static float SK_LOS[9];
+ static float q0 = 0.0f;
+ static float q1 = 0.0f;
+ static float q2 = 0.0f;
+ static float q3 = 1.0f;
+ static float vn = 0.0f;
+ static float ve = 0.0f;
+ static float vd = 0.0f;
+ static float pd = 0.0f;
+ static float ptd = 0.0f;
+ static float losPred[2];
+
+ // Transformation matrix from nav to body axes
+ float H_LOS[2][n_states];
+ float K_LOS[2][n_states];
+ Vector3f velNED_local;
+ Vector3f relVelSensor;
+
+ // Perform sequential fusion of optical flow measurements only with valid tilt and height
+ flowStates[1] = maxf(flowStates[1], statesAtFlowTime[9] + minFlowRng);
+ float heightAboveGndEst = flowStates[1] - statesAtFlowTime[9];
+ bool validTilt = Tnb.z.z > 0.71f;
+ if (validTilt)
{
- // Calculate observation jacobian and Kalman gain ignoring all states other than the terrain offset
- // This prevents the range finder measurement modifying any of the other filter states and significantly reduces computations
- SH_RNG[0] = SH_RNG[4]*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
- SH_RNG[1] = pd - ptd;
- SH_RNG[2] = 1/sq(SH_RNG[0]);
- SH_RNG[3] = 1/SH_RNG[0];
- for (uint8_t i = 0; i < n_states; i++) {
- H_RNG[i] = 0.0f;
- Kfusion[i] = 0.0f;
- }
- H_RNG[22] = -SH_RNG[3];
- SK_RNG[0] = 1/(R_RNG + SH_RNG[3]*(P[9][9]*SH_RNG[3] - P[22][9]*SH_RNG[3] + P[0][9]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][9]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][9]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][9]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[3]*(P[9][22]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[0][22]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][22]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][22]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][22]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) + SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4])*(P[9][0]*SH_RNG[3] - P[22][0]*SH_RNG[3] + P[0][0]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][0]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][0]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][0]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4])*(P[9][1]*SH_RNG[3] - P[22][1]*SH_RNG[3] + P[0][1]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][1]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][1]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][1]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4])*(P[9][2]*SH_RNG[3] - P[22][2]*SH_RNG[3] + P[0][2]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][2]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][2]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][2]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) + SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])*(P[9][3]*SH_RNG[3] - P[22][3]*SH_RNG[3] + P[0][3]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][3]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][3]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][3]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])));
- SK_RNG[1] = 2*q1 - 2*q3*SH_RNG[4];
- SK_RNG[2] = 2*q0 - 2*q2*SH_RNG[4];
- SK_RNG[3] = 2*q3 + 2*q1*SH_RNG[4];
- SK_RNG[4] = 2*q2 + 2*q0*SH_RNG[4];
- SK_RNG[5] = SH_RNG[2];
- Kfusion[22] = SK_RNG[0]*(P[22][9]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[22][0]*SH_RNG[1]*SK_RNG[2]*SK_RNG[5] - P[22][1]*SH_RNG[1]*SK_RNG[1]*SK_RNG[5] - P[22][2]*SH_RNG[1]*SK_RNG[4]*SK_RNG[5] + P[22][3]*SH_RNG[1]*SK_RNG[3]*SK_RNG[5]);
+ // Sequential fusion of XY components.
- // Calculate the innovation variance for data logging
- varInnovRng = 1.0f/SK_RNG[0];
+ // Calculate observation jacobians and Kalman gains
+ if (fuseOptFlowData)
+ {
+ // Copy required states to local variable names
+ q0 = statesAtFlowTime[0];
+ q1 = statesAtFlowTime[1];
+ q2 = statesAtFlowTime[2];
+ q3 = statesAtFlowTime[3];
+ vn = statesAtFlowTime[4];
+ ve = statesAtFlowTime[5];
+ vd = statesAtFlowTime[6];
+ pd = statesAtFlowTime[9];
+ ptd = flowStates[1];
+ velNED_local.x = vn;
+ velNED_local.y = ve;
+ velNED_local.z = vd;
+
+ // calculate range from ground plain to centre of sensor fov assuming flat earth
+ float range = heightAboveGndEst/Tnb_flow.z.z;
+
+ // calculate relative velocity in sensor frame
+ relVelSensor = Tnb_flow*velNED_local;
+
+ // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
+ losPred[0] = relVelSensor.y/range;
+ losPred[1] = -relVelSensor.x/range;
+
+ // Calculate common expressions for observation jacobians
+ SH_LOS[0] = sq(q0) - sq(q1) - sq(q2) + sq(q3);
+ SH_LOS[1] = vn*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) - vd*(2*q0*q2 - 2*q1*q3) + ve*(2*q0*q3 + 2*q1*q2);
+ SH_LOS[2] = ve*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + vd*(2*q0*q1 + 2*q2*q3) - vn*(2*q0*q3 - 2*q1*q2);
+ SH_LOS[3] = 1/(pd - ptd);
+ SH_LOS[4] = 1/sq(pd - ptd);
+
+ // Calculate common expressions for Kalman gains
+ SK_LOS[0] = 1.0f/((R_LOS + sq(omegaAcrossFlowTime[0] * moCompR_LOS)) + (SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3])*(P[0][0]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][0]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][0]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][0]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][0]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][0]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][0]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][0]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) + (SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3])*(P[0][1]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][1]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][1]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][1]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][1]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][1]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][1]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][1]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) - (SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3])*(P[0][2]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][2]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][2]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][2]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][2]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][2]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][2]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][2]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) + (SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3])*(P[0][3]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][3]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][3]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][3]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][3]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][3]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][3]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][3]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) - SH_LOS[0]*SH_LOS[1]*SH_LOS[4]*(P[0][9]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][9]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][9]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][9]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][9]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][9]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][9]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][9]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) + SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))*(P[0][4]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][4]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][4]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][4]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][4]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][4]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][4]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][4]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) + SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2)*(P[0][5]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][5]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][5]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][5]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][5]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][5]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][5]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][5]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))) - SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3)*(P[0][6]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3]) + P[1][6]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3]) - P[2][6]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) + 2*q2*SH_LOS[1]*SH_LOS[3]) + P[3][6]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3]) + P[5][6]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2) - P[6][6]*SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3) - P[9][6]*SH_LOS[0]*SH_LOS[1]*SH_LOS[4] + P[4][6]*SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3))));
+ SK_LOS[1] = 1.0f/((R_LOS + sq(omegaAcrossFlowTime[1] * moCompR_LOS))+ (SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3])*(P[0][0]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][0]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][0]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][0]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][0]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][0]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][0]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][0]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) + (SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3])*(P[0][1]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][1]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][1]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][1]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][1]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][1]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][1]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][1]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) + (SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3])*(P[0][2]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][2]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][2]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][2]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][2]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][2]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][2]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][2]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) - (SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3])*(P[0][3]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][3]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][3]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][3]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][3]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][3]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][3]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][3]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) - SH_LOS[0]*SH_LOS[2]*SH_LOS[4]*(P[0][9]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][9]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][9]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][9]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][9]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][9]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][9]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][9]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) + SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))*(P[0][5]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][5]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][5]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][5]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][5]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][5]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][5]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][5]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) - SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2)*(P[0][4]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][4]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][4]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][4]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][4]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][4]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][4]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][4]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))) + SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3)*(P[0][6]*(SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q0*SH_LOS[2]*SH_LOS[3]) + P[1][6]*(SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q1*SH_LOS[2]*SH_LOS[3]) + P[2][6]*(SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q2*SH_LOS[2]*SH_LOS[3]) - P[3][6]*(SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3]) - P[4][6]*SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2) + P[6][6]*SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3) - P[9][6]*SH_LOS[0]*SH_LOS[2]*SH_LOS[4] + P[5][6]*SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3))));
+ SK_LOS[2] = SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn);
+ SK_LOS[3] = SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn);
+ SK_LOS[4] = SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn);
+ SK_LOS[5] = SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn);
+ SK_LOS[6] = sq(q0) - sq(q1) + sq(q2) - sq(q3);
+ SK_LOS[7] = sq(q0) + sq(q1) - sq(q2) - sq(q3);
+ SK_LOS[8] = SH_LOS[3];
+
+ // Calculate common intermediate terms
+ float tempVar[9];
+ tempVar[0] = SH_LOS[0]*SK_LOS[6]*SK_LOS[8];
+ tempVar[1] = SH_LOS[0]*SH_LOS[2]*SH_LOS[4];
+ tempVar[2] = 2.0f*SH_LOS[2]*SK_LOS[8];
+ tempVar[3] = SH_LOS[0]*SK_LOS[8]*(2.0f*q0*q1 + 2.0f*q2*q3);
+ tempVar[4] = SH_LOS[0]*SK_LOS[8]*(2.0f*q0*q3 - 2.0f*q1*q2);
+ tempVar[5] = (SK_LOS[5] - q2*tempVar[2]);
+ tempVar[6] = (SK_LOS[2] - q3*tempVar[2]);
+ tempVar[7] = (SK_LOS[3] - q1*tempVar[2]);
+ tempVar[8] = (SK_LOS[4] + q0*tempVar[2]);
+
+ // calculate observation jacobians for X LOS rate
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[0][i] = 0;
+ H_LOS[0][0] = - SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) - 2*q0*SH_LOS[2]*SH_LOS[3];
+ H_LOS[0][1] = 2*q1*SH_LOS[2]*SH_LOS[3] - SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn);
+ H_LOS[0][2] = 2*q2*SH_LOS[2]*SH_LOS[3] - SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn);
+ H_LOS[0][3] = SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) - 2*q3*SH_LOS[2]*SH_LOS[3];
+ H_LOS[0][4] = SH_LOS[0]*SH_LOS[3]*(2*q0*q3 - 2*q1*q2);
+ H_LOS[0][5] = -SH_LOS[0]*SH_LOS[3]*(sq(q0) - sq(q1) + sq(q2) - sq(q3));
+ H_LOS[0][6] = -SH_LOS[0]*SH_LOS[3]*(2*q0*q1 + 2*q2*q3);
+ H_LOS[0][9] = tempVar[1];
+
+ // calculate Kalman gains for X LOS rate
+ K_LOS[0][0] = -(P[0][0]*tempVar[8] + P[0][1]*tempVar[7] - P[0][3]*tempVar[6] + P[0][2]*tempVar[5] - P[0][4]*tempVar[4] + P[0][6]*tempVar[3] - P[0][9]*tempVar[1] + P[0][5]*tempVar[0])/(R_LOS + tempVar[8]*(P[0][0]*tempVar[8] + P[1][0]*tempVar[7] + P[2][0]*tempVar[5] - P[3][0]*tempVar[6] - P[4][0]*tempVar[4] + P[6][0]*tempVar[3] - P[9][0]*tempVar[1] + P[5][0]*tempVar[0]) + tempVar[7]*(P[0][1]*tempVar[8] + P[1][1]*tempVar[7] + P[2][1]*tempVar[5] - P[3][1]*tempVar[6] - P[4][1]*tempVar[4] + P[6][1]*tempVar[3] - P[9][1]*tempVar[1] + P[5][1]*tempVar[0]) + tempVar[5]*(P[0][2]*tempVar[8] + P[1][2]*tempVar[7] + P[2][2]*tempVar[5] - P[3][2]*tempVar[6] - P[4][2]*tempVar[4] + P[6][2]*tempVar[3] - P[9][2]*tempVar[1] + P[5][2]*tempVar[0]) - tempVar[6]*(P[0][3]*tempVar[8] + P[1][3]*tempVar[7] + P[2][3]*tempVar[5] - P[3][3]*tempVar[6] - P[4][3]*tempVar[4] + P[6][3]*tempVar[3] - P[9][3]*tempVar[1] + P[5][3]*tempVar[0]) - tempVar[4]*(P[0][4]*tempVar[8] + P[1][4]*tempVar[7] + P[2][4]*tempVar[5] - P[3][4]*tempVar[6] - P[4][4]*tempVar[4] + P[6][4]*tempVar[3] - P[9][4]*tempVar[1] + P[5][4]*tempVar[0]) + tempVar[3]*(P[0][6]*tempVar[8] + P[1][6]*tempVar[7] + P[2][6]*tempVar[5] - P[3][6]*tempVar[6] - P[4][6]*tempVar[4] + P[6][6]*tempVar[3] - P[9][6]*tempVar[1] + P[5][6]*tempVar[0]) - tempVar[1]*(P[0][9]*tempVar[8] + P[1][9]*tempVar[7] + P[2][9]*tempVar[5] - P[3][9]*tempVar[6] - P[4][9]*tempVar[4] + P[6][9]*tempVar[3] - P[9][9]*tempVar[1] + P[5][9]*tempVar[0]) + tempVar[0]*(P[0][5]*tempVar[8] + P[1][5]*tempVar[7] + P[2][5]*tempVar[5] - P[3][5]*tempVar[6] - P[4][5]*tempVar[4] + P[6][5]*tempVar[3] - P[9][5]*tempVar[1] + P[5][5]*tempVar[0]));
+ K_LOS[0][1] = -SK_LOS[1]*(P[1][0]*tempVar[8] + P[1][1]*tempVar[7] - P[1][3]*tempVar[6] + P[1][2]*tempVar[5] - P[1][4]*tempVar[4] + P[1][6]*tempVar[3] - P[1][9]*tempVar[1] + P[1][5]*tempVar[0]);
+ K_LOS[0][2] = -SK_LOS[1]*(P[2][0]*tempVar[8] + P[2][1]*tempVar[7] - P[2][3]*tempVar[6] + P[2][2]*tempVar[5] - P[2][4]*tempVar[4] + P[2][6]*tempVar[3] - P[2][9]*tempVar[1] + P[2][5]*tempVar[0]);
+ K_LOS[0][3] = -SK_LOS[1]*(P[3][0]*tempVar[8] + P[3][1]*tempVar[7] - P[3][3]*tempVar[6] + P[3][2]*tempVar[5] - P[3][4]*tempVar[4] + P[3][6]*tempVar[3] - P[3][9]*tempVar[1] + P[3][5]*tempVar[0]);
+ K_LOS[0][4] = -SK_LOS[1]*(P[4][0]*tempVar[8] + P[4][1]*tempVar[7] - P[4][3]*tempVar[6] + P[4][2]*tempVar[5] - P[4][4]*tempVar[4] + P[4][6]*tempVar[3] - P[4][9]*tempVar[1] + P[4][5]*tempVar[0]);
+ K_LOS[0][5] = -SK_LOS[1]*(P[5][0]*tempVar[8] + P[5][1]*tempVar[7] - P[5][3]*tempVar[6] + P[5][2]*tempVar[5] - P[5][4]*tempVar[4] + P[5][6]*tempVar[3] - P[5][9]*tempVar[1] + P[5][5]*tempVar[0]);
+ K_LOS[0][6] = -SK_LOS[1]*(P[6][0]*tempVar[8] + P[6][1]*tempVar[7] - P[6][3]*tempVar[6] + P[6][2]*tempVar[5] - P[6][4]*tempVar[4] + P[6][6]*tempVar[3] - P[6][9]*tempVar[1] + P[6][5]*tempVar[0]);
+ K_LOS[0][7] = -SK_LOS[1]*(P[7][0]*tempVar[8] + P[7][1]*tempVar[7] - P[7][3]*tempVar[6] + P[7][2]*tempVar[5] - P[7][4]*tempVar[4] + P[7][6]*tempVar[3] - P[7][9]*tempVar[1] + P[7][5]*tempVar[0]);
+ K_LOS[0][8] = -SK_LOS[1]*(P[8][0]*tempVar[8] + P[8][1]*tempVar[7] - P[8][3]*tempVar[6] + P[8][2]*tempVar[5] - P[8][4]*tempVar[4] + P[8][6]*tempVar[3] - P[8][9]*tempVar[1] + P[8][5]*tempVar[0]);
+ K_LOS[0][9] = -SK_LOS[1]*(P[9][0]*tempVar[8] + P[9][1]*tempVar[7] - P[9][3]*tempVar[6] + P[9][2]*tempVar[5] - P[9][4]*tempVar[4] + P[9][6]*tempVar[3] - P[9][9]*tempVar[1] + P[9][5]*tempVar[0]);
+ K_LOS[0][10] = -SK_LOS[1]*(P[10][0]*tempVar[8] + P[10][1]*tempVar[7] - P[10][3]*tempVar[6] + P[10][2]*tempVar[5] - P[10][4]*tempVar[4] + P[10][6]*tempVar[3] - P[10][9]*tempVar[1] + P[10][5]*tempVar[0]);
+ K_LOS[0][11] = -SK_LOS[1]*(P[11][0]*tempVar[8] + P[11][1]*tempVar[7] - P[11][3]*tempVar[6] + P[11][2]*tempVar[5] - P[11][4]*tempVar[4] + P[11][6]*tempVar[3] - P[11][9]*tempVar[1] + P[11][5]*tempVar[0]);
+ K_LOS[0][12] = -SK_LOS[1]*(P[12][0]*tempVar[8] + P[12][1]*tempVar[7] - P[12][3]*tempVar[6] + P[12][2]*tempVar[5] - P[12][4]*tempVar[4] + P[12][6]*tempVar[3] - P[12][9]*tempVar[1] + P[12][5]*tempVar[0]);
+ // only height measurements are allowed to modify the Z bias state to improve the stability of the estimate
+ K_LOS[0][13] = 0.0f;//-SK_LOS[1]*(P[13][0]*tempVar[8] + P[13][1]*tempVar[7] - P[13][3]*tempVar[6] + P[13][2]*tempVar[5] - P[13][4]*tempVar[4] + P[13][6]*tempVar[3] - P[13][9]*tempVar[1] + P[13][5]*tempVar[0]);
+ if (inhibitWindStates) {
+ K_LOS[0][14] = -SK_LOS[1]*(P[14][0]*tempVar[8] + P[14][1]*tempVar[7] - P[14][3]*tempVar[6] + P[14][2]*tempVar[5] - P[14][4]*tempVar[4] + P[14][6]*tempVar[3] - P[14][9]*tempVar[1] + P[14][5]*tempVar[0]);
+ K_LOS[0][15] = -SK_LOS[1]*(P[15][0]*tempVar[8] + P[15][1]*tempVar[7] - P[15][3]*tempVar[6] + P[15][2]*tempVar[5] - P[15][4]*tempVar[4] + P[15][6]*tempVar[3] - P[15][9]*tempVar[1] + P[15][5]*tempVar[0]);
+ } else {
+ K_LOS[0][14] = 0.0f;
+ K_LOS[0][15] = 0.0f;
+ }
+ if (inhibitMagStates) {
+ K_LOS[0][16] = -SK_LOS[1]*(P[16][0]*tempVar[8] + P[16][1]*tempVar[7] - P[16][3]*tempVar[6] + P[16][2]*tempVar[5] - P[16][4]*tempVar[4] + P[16][6]*tempVar[3] - P[16][9]*tempVar[1] + P[16][5]*tempVar[0]);
+ K_LOS[0][17] = -SK_LOS[1]*(P[17][0]*tempVar[8] + P[17][1]*tempVar[7] - P[17][3]*tempVar[6] + P[17][2]*tempVar[5] - P[17][4]*tempVar[4] + P[17][6]*tempVar[3] - P[17][9]*tempVar[1] + P[17][5]*tempVar[0]);
+ K_LOS[0][18] = -SK_LOS[1]*(P[18][0]*tempVar[8] + P[18][1]*tempVar[7] - P[18][3]*tempVar[6] + P[18][2]*tempVar[5] - P[18][4]*tempVar[4] + P[18][6]*tempVar[3] - P[18][9]*tempVar[1] + P[18][5]*tempVar[0]);
+ K_LOS[0][19] = -SK_LOS[1]*(P[19][0]*tempVar[8] + P[19][1]*tempVar[7] - P[19][3]*tempVar[6] + P[19][2]*tempVar[5] - P[19][4]*tempVar[4] + P[19][6]*tempVar[3] - P[19][9]*tempVar[1] + P[19][5]*tempVar[0]);
+ K_LOS[0][20] = -SK_LOS[1]*(P[20][0]*tempVar[8] + P[20][1]*tempVar[7] - P[20][3]*tempVar[6] + P[20][2]*tempVar[5] - P[20][4]*tempVar[4] + P[20][6]*tempVar[3] - P[20][9]*tempVar[1] + P[20][5]*tempVar[0]);
+ K_LOS[0][21] = -SK_LOS[1]*(P[21][0]*tempVar[8] + P[21][1]*tempVar[7] - P[21][3]*tempVar[6] + P[21][2]*tempVar[5] - P[21][4]*tempVar[4] + P[21][6]*tempVar[3] - P[21][9]*tempVar[1] + P[21][5]*tempVar[0]);
+ } else {
+ for (uint8_t i = 16; i < n_states; i++) {
+ K_LOS[0][i] = 0.0f;
+ }
+ }
- // Calculate the measurement innovation
- rngPred = (ptd - pd)/cosRngTilt;
- innovRng = rngPred - rngMea;
+ // calculate innovation variance and innovation for X axis observation
+ varInnovOptFlow[0] = 1.0f/SK_LOS[0];
+ innovOptFlow[0] = losPred[0] - flowRadXYcomp[0];
+
+ // calculate intermediate common variables
+ tempVar[0] = 2.0f*SH_LOS[1]*SK_LOS[8];
+ tempVar[1] = (SK_LOS[2] + q0*tempVar[0]);
+ tempVar[2] = (SK_LOS[5] - q1*tempVar[0]);
+ tempVar[3] = (SK_LOS[3] + q2*tempVar[0]);
+ tempVar[4] = (SK_LOS[4] + q3*tempVar[0]);
+ tempVar[5] = SH_LOS[0]*SK_LOS[8]*(2*q0*q3 + 2*q1*q2);
+ tempVar[6] = SH_LOS[0]*SK_LOS[8]*(2*q0*q2 - 2*q1*q3);
+ tempVar[7] = SH_LOS[0]*SH_LOS[1]*SH_LOS[4];
+ tempVar[8] = SH_LOS[0]*SK_LOS[7]*SK_LOS[8];
+
+ // Calculate observation jacobians for Y LOS rate
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[1][i] = 0;
+ H_LOS[1][0] = SH_LOS[0]*SH_LOS[3]*(2*q3*ve - 2*q2*vd + 2*q0*vn) + 2*q0*SH_LOS[1]*SH_LOS[3];
+ H_LOS[1][1] = SH_LOS[0]*SH_LOS[3]*(2*q3*vd + 2*q2*ve + 2*q1*vn) - 2*q1*SH_LOS[1]*SH_LOS[3];
+ H_LOS[1][2] = - SH_LOS[0]*SH_LOS[3]*(2*q0*vd - 2*q1*ve + 2*q2*vn) - 2*q2*SH_LOS[1]*SH_LOS[3];
+ H_LOS[1][3] = SH_LOS[0]*SH_LOS[3]*(2*q1*vd + 2*q0*ve - 2*q3*vn) + 2*q3*SH_LOS[1]*SH_LOS[3];
+ H_LOS[1][4] = SH_LOS[0]*SH_LOS[3]*(sq(q0) + sq(q1) - sq(q2) - sq(q3));
+ H_LOS[1][5] = SH_LOS[0]*SH_LOS[3]*(2*q0*q3 + 2*q1*q2);
+ H_LOS[1][6] = -SH_LOS[0]*SH_LOS[3]*(2*q0*q2 - 2*q1*q3);
+ H_LOS[1][9] = -tempVar[7];
+
+ // Calculate Kalman gains for Y LOS rate
+ K_LOS[1][0] = SK_LOS[0]*(P[0][0]*tempVar[1] + P[0][1]*tempVar[2] - P[0][2]*tempVar[3] + P[0][3]*tempVar[4] + P[0][5]*tempVar[5] - P[0][6]*tempVar[6] - P[0][9]*tempVar[7] + P[0][4]*tempVar[8]);
+ K_LOS[1][1] = SK_LOS[0]*(P[1][0]*tempVar[1] + P[1][1]*tempVar[2] - P[1][2]*tempVar[3] + P[1][3]*tempVar[4] + P[1][5]*tempVar[5] - P[1][6]*tempVar[6] - P[1][9]*tempVar[7] + P[1][4]*tempVar[8]);
+ K_LOS[1][2] = SK_LOS[0]*(P[2][0]*tempVar[1] + P[2][1]*tempVar[2] - P[2][2]*tempVar[3] + P[2][3]*tempVar[4] + P[2][5]*tempVar[5] - P[2][6]*tempVar[6] - P[2][9]*tempVar[7] + P[2][4]*tempVar[8]);
+ K_LOS[1][3] = SK_LOS[0]*(P[3][0]*tempVar[1] + P[3][1]*tempVar[2] - P[3][2]*tempVar[3] + P[3][3]*tempVar[4] + P[3][5]*tempVar[5] - P[3][6]*tempVar[6] - P[3][9]*tempVar[7] + P[3][4]*tempVar[8]);
+ K_LOS[1][4] = SK_LOS[0]*(P[4][0]*tempVar[1] + P[4][1]*tempVar[2] - P[4][2]*tempVar[3] + P[4][3]*tempVar[4] + P[4][5]*tempVar[5] - P[4][6]*tempVar[6] - P[4][9]*tempVar[7] + P[4][4]*tempVar[8]);
+ K_LOS[1][5] = SK_LOS[0]*(P[5][0]*tempVar[1] + P[5][1]*tempVar[2] - P[5][2]*tempVar[3] + P[5][3]*tempVar[4] + P[5][5]*tempVar[5] - P[5][6]*tempVar[6] - P[5][9]*tempVar[7] + P[5][4]*tempVar[8]);
+ K_LOS[1][6] = SK_LOS[0]*(P[6][0]*tempVar[1] + P[6][1]*tempVar[2] - P[6][2]*tempVar[3] + P[6][3]*tempVar[4] + P[6][5]*tempVar[5] - P[6][6]*tempVar[6] - P[6][9]*tempVar[7] + P[6][4]*tempVar[8]);
+ K_LOS[1][7] = SK_LOS[0]*(P[7][0]*tempVar[1] + P[7][1]*tempVar[2] - P[7][2]*tempVar[3] + P[7][3]*tempVar[4] + P[7][5]*tempVar[5] - P[7][6]*tempVar[6] - P[7][9]*tempVar[7] + P[7][4]*tempVar[8]);
+ K_LOS[1][8] = SK_LOS[0]*(P[8][0]*tempVar[1] + P[8][1]*tempVar[2] - P[8][2]*tempVar[3] + P[8][3]*tempVar[4] + P[8][5]*tempVar[5] - P[8][6]*tempVar[6] - P[8][9]*tempVar[7] + P[8][4]*tempVar[8]);
+ K_LOS[1][9] = SK_LOS[0]*(P[9][0]*tempVar[1] + P[9][1]*tempVar[2] - P[9][2]*tempVar[3] + P[9][3]*tempVar[4] + P[9][5]*tempVar[5] - P[9][6]*tempVar[6] - P[9][9]*tempVar[7] + P[9][4]*tempVar[8]);
+ K_LOS[1][10] = SK_LOS[0]*(P[10][0]*tempVar[1] + P[10][1]*tempVar[2] - P[10][2]*tempVar[3] + P[10][3]*tempVar[4] + P[10][5]*tempVar[5] - P[10][6]*tempVar[6] - P[10][9]*tempVar[7] + P[10][4]*tempVar[8]);
+ K_LOS[1][11] = SK_LOS[0]*(P[11][0]*tempVar[1] + P[11][1]*tempVar[2] - P[11][2]*tempVar[3] + P[11][3]*tempVar[4] + P[11][5]*tempVar[5] - P[11][6]*tempVar[6] - P[11][9]*tempVar[7] + P[11][4]*tempVar[8]);
+ K_LOS[1][12] = SK_LOS[0]*(P[12][0]*tempVar[1] + P[12][1]*tempVar[2] - P[12][2]*tempVar[3] + P[12][3]*tempVar[4] + P[12][5]*tempVar[5] - P[12][6]*tempVar[6] - P[12][9]*tempVar[7] + P[12][4]*tempVar[8]);
+ // only height measurements are allowed to modify the Z bias state to improve the stability of the estimate
+ K_LOS[1][13] = 0.0f;//SK_LOS[0]*(P[13][0]*tempVar[1] + P[13][1]*tempVar[2] - P[13][2]*tempVar[3] + P[13][3]*tempVar[4] + P[13][5]*tempVar[5] - P[13][6]*tempVar[6] - P[13][9]*tempVar[7] + P[13][4]*tempVar[8]);
+ if (inhibitWindStates) {
+ K_LOS[1][14] = SK_LOS[0]*(P[14][0]*tempVar[1] + P[14][1]*tempVar[2] - P[14][2]*tempVar[3] + P[14][3]*tempVar[4] + P[14][5]*tempVar[5] - P[14][6]*tempVar[6] - P[14][9]*tempVar[7] + P[14][4]*tempVar[8]);
+ K_LOS[1][15] = SK_LOS[0]*(P[15][0]*tempVar[1] + P[15][1]*tempVar[2] - P[15][2]*tempVar[3] + P[15][3]*tempVar[4] + P[15][5]*tempVar[5] - P[15][6]*tempVar[6] - P[15][9]*tempVar[7] + P[15][4]*tempVar[8]);
+ } else {
+ K_LOS[1][14] = 0.0f;
+ K_LOS[1][15] = 0.0f;
+ }
+ if (inhibitMagStates) {
+ K_LOS[1][16] = SK_LOS[0]*(P[16][0]*tempVar[1] + P[16][1]*tempVar[2] - P[16][2]*tempVar[3] + P[16][3]*tempVar[4] + P[16][5]*tempVar[5] - P[16][6]*tempVar[6] - P[16][9]*tempVar[7] + P[16][4]*tempVar[8]);
+ K_LOS[1][17] = SK_LOS[0]*(P[17][0]*tempVar[1] + P[17][1]*tempVar[2] - P[17][2]*tempVar[3] + P[17][3]*tempVar[4] + P[17][5]*tempVar[5] - P[17][6]*tempVar[6] - P[17][9]*tempVar[7] + P[17][4]*tempVar[8]);
+ K_LOS[1][18] = SK_LOS[0]*(P[18][0]*tempVar[1] + P[18][1]*tempVar[2] - P[18][2]*tempVar[3] + P[18][3]*tempVar[4] + P[18][5]*tempVar[5] - P[18][6]*tempVar[6] - P[18][9]*tempVar[7] + P[18][4]*tempVar[8]);
+ K_LOS[1][19] = SK_LOS[0]*(P[19][0]*tempVar[1] + P[19][1]*tempVar[2] - P[19][2]*tempVar[3] + P[19][3]*tempVar[4] + P[19][5]*tempVar[5] - P[19][6]*tempVar[6] - P[19][9]*tempVar[7] + P[19][4]*tempVar[8]);
+ K_LOS[1][20] = SK_LOS[0]*(P[20][0]*tempVar[1] + P[20][1]*tempVar[2] - P[20][2]*tempVar[3] + P[20][3]*tempVar[4] + P[20][5]*tempVar[5] - P[20][6]*tempVar[6] - P[20][9]*tempVar[7] + P[20][4]*tempVar[8]);
+ K_LOS[1][21] = SK_LOS[0]*(P[21][0]*tempVar[1] + P[21][1]*tempVar[2] - P[21][2]*tempVar[3] + P[21][3]*tempVar[4] + P[21][5]*tempVar[5] - P[21][6]*tempVar[6] - P[21][9]*tempVar[7] + P[21][4]*tempVar[8]);
+ } else {
+ for (uint8_t i = 16; i < n_states; i++) {
+ K_LOS[1][i] = 0.0f;
+ }
+ }
- // calculate the innovation consistency test ratio
- auxRngTestRatio = sq(innovRng) / (sq(rngInnovGate) * varInnovRng);
+ // calculate variance and innovation for Y observation
+ varInnovOptFlow[1] = 1.0f/SK_LOS[1];
+ innovOptFlow[1] = losPred[1] - flowRadXYcomp[1];
- // Check the innovation for consistency and don't fuse if out of bounds
- if (auxRngTestRatio < 1.0f)
- {
- // correct the state vector
- states[22] = states[22] - Kfusion[22] * innovRng;
+ }
- // correct the covariance P = (I - K*H)*P
- P[22][22] = P[22][22] - Kfusion[22] * H_RNG[22] * P[22][22];
- P[22][22] = ConstrainFloat(P[22][22], 0.0f, 10000.0f);
+ // loop through the X and Y observations and fuse them sequentially
+ for (uint8_t obsIndex = 0; obsIndex < 2; obsIndex++) {
+ // Check the innovation for consistency and don't fuse if > 5Sigma
+ if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 25.0f) {
+ // correct the state vector
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ states[j] = states[j] - K_LOS[obsIndex][j] * innovOptFlow[obsIndex];
+ }
+ // normalise the quaternion states
+ float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12f)
+ {
+ for (uint8_t j= 0; j<=3; j++)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[j] = states[j] * quatMagInv;
+ }
+ }
+ // correct the covariance P = (I - K*H)*P
+ // take advantage of the empty columns in KH to reduce the
+ // number of operations
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j <= 6; j++)
+ {
+ KH[i][j] = K_LOS[obsIndex][i] * H_LOS[obsIndex][j];
+ }
+ for (uint8_t j = 7; j <= 8; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ KH[i][9] = K_LOS[obsIndex][i] * H_LOS[obsIndex][9];
+ for (uint8_t j = 10; j < n_states; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ KHP[i][j] = 0.0f;
+ for (uint8_t k = 0; k <= 6; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
+ }
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
}
+ ForceSymmetry();
+ ConstrainVariances();
}
-
-}
-
-void AttPosEKF::FuseOptFlow()
-{
-// static uint8_t obsIndex;
-// static float SH_LOS[13];
-// static float SKK_LOS[15];
-// static float SK_LOS[2];
-// static float q0 = 0.0f;
-// static float q1 = 0.0f;
-// static float q2 = 0.0f;
-// static float q3 = 1.0f;
-// static float vn = 0.0f;
-// static float ve = 0.0f;
-// static float vd = 0.0f;
-// static float pd = 0.0f;
-// static float ptd = 0.0f;
-// static float R_LOS = 0.01f;
-// static float losPred[2];
-
-// // Transformation matrix from nav to body axes
-// Mat3f Tnb_local;
-// // Transformation matrix from body to sensor axes
-// // assume camera is aligned with Z body axis plus a misalignment
-// // defined by 3 small angles about X, Y and Z body axis
-// Mat3f Tbs;
-// Tbs.x.y = a3;
-// Tbs.y.x = -a3;
-// Tbs.x.z = -a2;
-// Tbs.z.x = a2;
-// Tbs.y.z = a1;
-// Tbs.z.y = -a1;
-// // Transformation matrix from navigation to sensor axes
-// Mat3f Tns;
-// float H_LOS[n_states];
-// for (uint8_t i = 0; i < n_states; i++) {
-// H_LOS[i] = 0.0f;
-// }
-// Vector3f velNED_local;
-// Vector3f relVelSensor;
-
-// // Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg.
-// if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f)
-// {
-// // Sequential fusion of XY components to spread processing load across
-// // two prediction time steps.
-
-// // Calculate observation jacobians and Kalman gains
-// if (fuseOptFlowData)
-// {
-// // Copy required states to local variable names
-// q0 = statesAtOptFlowTime[0];
-// q1 = statesAtOptFlowTime[1];
-// q2 = statesAtOptFlowTime[2];
-// q3 = statesAtOptFlowTime[3];
-// vn = statesAtOptFlowTime[4];
-// ve = statesAtOptFlowTime[5];
-// vd = statesAtOptFlowTime[6];
-// pd = statesAtOptFlowTime[9];
-// ptd = statesAtOptFlowTime[22];
-// velNED_local.x = vn;
-// velNED_local.y = ve;
-// velNED_local.z = vd;
-
-// // calculate rotation from NED to body axes
-// float q00 = sq(q0);
-// float q11 = sq(q1);
-// float q22 = sq(q2);
-// float q33 = sq(q3);
-// float q01 = q0 * q1;
-// float q02 = q0 * q2;
-// float q03 = q0 * q3;
-// float q12 = q1 * q2;
-// float q13 = q1 * q3;
-// float q23 = q2 * q3;
-// Tnb_local.x.x = q00 + q11 - q22 - q33;
-// Tnb_local.y.y = q00 - q11 + q22 - q33;
-// Tnb_local.z.z = q00 - q11 - q22 + q33;
-// Tnb_local.y.x = 2*(q12 - q03);
-// Tnb_local.z.x = 2*(q13 + q02);
-// Tnb_local.x.y = 2*(q12 + q03);
-// Tnb_local.z.y = 2*(q23 - q01);
-// Tnb_local.x.z = 2*(q13 - q02);
-// Tnb_local.y.z = 2*(q23 + q01);
-
-// // calculate transformation from NED to sensor axes
-// Tns = Tbs*Tnb_local;
-
-// // calculate range from ground plain to centre of sensor fov assuming flat earth
-// float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f);
-
-// // calculate relative velocity in sensor frame
-// relVelSensor = Tns*velNED_local;
-
-// // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
-// losPred[0] = relVelSensor.y/range;
-// losPred[1] = -relVelSensor.x/range;
-
-// //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y);
-// //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y);
-// //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range);
-
-// // Calculate observation jacobians
-// SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
-// SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
-// SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
-// SH_LOS[3] = 1/(pd - ptd);
-// SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2;
-// SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3;
-// SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1;
-// SH_LOS[7] = 1/sq(pd - ptd);
-// SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1;
-// SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0;
-// SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3;
-// SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0;
-// SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2;
-
-// for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
-// H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
-// H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
-// H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3);
-// H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
-// H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
-// H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3));
-// H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3));
-// H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
-// H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
-
-// // Calculate Kalman gain
-// SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3);
-// SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3);
-// SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3);
-// SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3);
-// SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3);
-// SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3);
-// SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
-// SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
-// SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
-// SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]);
-// SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
-// SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
-// SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
-// SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]);
-// SKK_LOS[14] = SH_LOS[0];
-
-// SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]));
-// Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
-// varInnovOptFlow[0] = 1.0f/SK_LOS[0];
-// innovOptFlow[0] = losPred[0] - losData[0];
-
-// // set the observation index to 1 to fuse the y component next time round and reset the commence fusion flag
-// obsIndex = 1;
-// fuseOptFlowData = false;
-// }
-// else if (obsIndex == 1) // we are now fusing the Y measurement
-// {
-// // Calculate observation jacobians
-// for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
-// H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
-// H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
-// H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
-// H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1);
-// H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
-// H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3));
-// H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3));
-// H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
-// H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
-
-// // Calculate Kalman gains
-// SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]));
-// Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
-// varInnovOptFlow[1] = 1.0f/SK_LOS[1];
-// innovOptFlow[1] = losPred[1] - losData[1];
-
-// // reset the observation index
-// obsIndex = 0;
-// fuseOptFlowData = false;
-// }
-
-// // Check the innovation for consistency and don't fuse if > 3Sigma
-// if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f)
-// {
-// // correct the state vector
-// for (uint8_t j = 0; j < n_states; j++)
-// {
-// states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex];
-// }
-// // normalise the quaternion states
-// float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
-// if (quatMag > 1e-12f)
-// {
-// for (uint8_t j= 0; j<=3; j++)
-// {
-// float quatMagInv = 1.0f/quatMag;
-// states[j] = states[j] * quatMagInv;
-// }
-// }
-// // correct the covariance P = (I - K*H)*P
-// // take advantage of the empty columns in KH to reduce the
-// // number of operations
-// for (uint8_t i = 0; i < n_states; i++)
-// {
-// for (uint8_t j = 0; j <= 6; j++)
-// {
-// KH[i][j] = Kfusion[i] * H_LOS[j];
-// }
-// for (uint8_t j = 7; j <= 8; j++)
-// {
-// KH[i][j] = 0.0f;
-// }
-// KH[i][9] = Kfusion[i] * H_LOS[9];
-// for (uint8_t j = 10; j <= 21; j++)
-// {
-// KH[i][j] = 0.0f;
-// }
-// KH[i][22] = Kfusion[i] * H_LOS[22];
-// }
-// for (uint8_t i = 0; i < n_states; i++)
-// {
-// for (uint8_t j = 0; j < n_states; j++)
-// {
-// KHP[i][j] = 0.0f;
-// for (uint8_t k = 0; k <= 6; k++)
-// {
-// KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
-// }
-// KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
-// KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j];
-// }
-// }
-// }
-// for (uint8_t i = 0; i < n_states; i++)
-// {
-// for (uint8_t j = 0; j < n_states; j++)
-// {
-// P[i][j] = P[i][j] - KHP[i][j];
-// }
-// }
-// ForceSymmetry();
-// ConstrainVariances();
-// }
}
/*
@@ -2192,27 +2019,29 @@ Estimation of optical flow sensor focal length scale factor and terrain height u
This fiter requires optical flow rates that are not motion compensated
Range to ground measurement is assumed to be via a narrow beam type sensor - eg laser
*/
-void AttPosEKF::GroundEKF()
+void AttPosEKF::OpticalFlowEKF()
{
// propagate ground position state noise each time this is called using the difference in position since the last observations and an RMS gradient assumption
// limit distance to prevent intialisation afer bad gps causing bad numerical conditioning
if (!inhibitGndState) {
float distanceTravelledSq;
- distanceTravelledSq = sq(statesAtRngTime[7] - prevPosN) + sq(statesAtRngTime[8] - prevPosE);
- prevPosN = statesAtRngTime[7];
- prevPosE = statesAtRngTime[8];
+ if (fuseRngData) {
+ distanceTravelledSq = sq(statesAtRngTime[7] - prevPosN) + sq(statesAtRngTime[8] - prevPosE);
+ prevPosN = statesAtRngTime[7];
+ prevPosE = statesAtRngTime[8];
+ } else if (fuseOptFlowData) {
+ distanceTravelledSq = sq(statesAtFlowTime[7] - prevPosN) + sq(statesAtFlowTime[8] - prevPosE);
+ prevPosN = statesAtFlowTime[7];
+ prevPosE = statesAtFlowTime[8];
+ } else {
+ return;
+ }
distanceTravelledSq = min(distanceTravelledSq, 100.0f);
Popt[1][1] += (distanceTravelledSq * sq(gndHgtSigma));
}
- // we aren't using optical flow measurements in this hacked implementation so set the covariances for this state to zero to avoid numerical problems
- Popt[0][0] = 0.0f;
- Popt[0][1] = 0.0f;
- Popt[1][0] = 0.0f;
- // Fuse range finder data
- // Need to check that our range finder tilt angle is less than 30 degrees
- float cosRngTilt = - Tbn.z.x * sinf(rngFinderPitch) + Tbn.z.z * cosf(rngFinderPitch);
- if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f) {
+ // fuse range finder data
+ if (fuseRngData) {
float range; // range from camera to centre of image
float q0; // quaternion at optical flow measurement time
float q1; // quaternion at optical flow measurement time
@@ -2266,10 +2095,7 @@ void AttPosEKF::GroundEKF()
flowStates[i] -= K_RNG[i] * innovRng;
}
// constrain the states
-
- // constrain focal length to 0.1 to 10 mm
flowStates[0] = ConstrainFloat(flowStates[0], 0.1f, 10.0f);
- // constrain altitude
flowStates[1] = maxf(flowStates[1], statesAtRngTime[9] + minFlowRng);
// correct the covariance matrix
@@ -2285,6 +2111,132 @@ void AttPosEKF::GroundEKF()
Popt[1][0] = Popt[0][1];
}
}
+
+ if (fuseOptFlowData) {
+ Vector3f vel; // velocity of sensor relative to ground in NED axes
+ Vector3f relVelSensor; // velocity of sensor relative to ground in sensor axes
+ float losPred[2]; // predicted optical flow angular rate measurements
+ float range; // range from camera to centre of image
+ float q0; // quaternion at optical flow measurement time
+ float q1; // quaternion at optical flow measurement time
+ float q2; // quaternion at optical flow measurement time
+ float q3; // quaternion at optical flow measurement time
+ float HP[2];
+ float SH_OPT[6];
+ float SK_OPT[3];
+ float K_OPT[2][2];
+ float H_OPT[2][2];
+ float nextPopt[2][2];
+
+ // propagate scale factor state noise
+ if (!inhibitScaleState) {
+ Popt[0][0] += 1e-8f;
+ } else {
+ Popt[0][0] = 0.0f;
+ }
+
+ // Copy required states to local variable names
+ q0 = statesAtFlowTime[0];
+ q1 = statesAtFlowTime[1];
+ q2 = statesAtFlowTime[2];
+ q3 = statesAtFlowTime[3];
+ vel.x = statesAtFlowTime[4];
+ vel.y = statesAtFlowTime[5];
+ vel.z = statesAtFlowTime[6];
+
+ // constrain terrain height to be below the vehicle
+ flowStates[1] = maxf(flowStates[1], statesAtFlowTime[9] + minFlowRng);
+
+ // estimate range to centre of image
+ range = (flowStates[1] - statesAtFlowTime[9]) / Tnb_flow.z.z;
+
+ // calculate relative velocity in sensor frame
+ relVelSensor = Tnb_flow * vel;
+
+ // divide velocity by range, subtract body rates and apply scale factor to
+ // get predicted sensed angular optical rates relative to X and Y sensor axes
+ losPred[0] = flowStates[0]*( relVelSensor.y / range) - omegaAcrossFlowTime[0];
+ losPred[1] = flowStates[0]*(-relVelSensor.x / range) - omegaAcrossFlowTime[1];
+
+ // calculate innovations
+ auxFlowObsInnov[0] = losPred[0] - flowRadXY[0];
+ auxFlowObsInnov[1] = losPred[1] - flowRadXY[1];
+
+ // calculate Kalman gains
+ SH_OPT[0] = sq(q0) - sq(q1) - sq(q2) + sq(q3);
+ SH_OPT[1] = vel.x*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + vel.y*(2*q0*q3 + 2*q1*q2) - vel.z*(2*q0*q2 - 2*q1*q3);
+ SH_OPT[2] = vel.y*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) - vel.x*(2*q0*q3 - 2*q1*q2) + vel.z*(2*q0*q1 + 2*q2*q3);
+ SH_OPT[3] = statesAtFlowTime[9] - flowStates[1];
+ SH_OPT[4] = 1.0f/sq(SH_OPT[3]);
+ SH_OPT[5] = 1.0f/SH_OPT[3];
+ float SH015 = SH_OPT[0]*SH_OPT[1]*SH_OPT[5];
+ float SH025 = SH_OPT[0]*SH_OPT[2]*SH_OPT[5];
+ float SH014 = SH_OPT[0]*SH_OPT[1]*SH_OPT[4];
+ float SH024 = SH_OPT[0]*SH_OPT[2]*SH_OPT[4];
+ SK_OPT[0] = 1.0f/(R_LOS + SH015*(Popt[0][0]*SH015 + Popt[1][0]*flowStates[0]*SH014) + flowStates[0]*SH014*(Popt[0][1]*SH015 + Popt[1][1]*flowStates[0]*SH014));
+ SK_OPT[1] = 1.0f/(R_LOS + SH025*(Popt[0][0]*SH025 + Popt[1][0]*flowStates[0]*SH024) + flowStates[0]*SH024*(Popt[0][1]*SH025 + Popt[1][1]*flowStates[0]*SH024));
+ SK_OPT[2] = SH_OPT[0];
+ if (!inhibitScaleState) {
+ K_OPT[0][0] = -SK_OPT[1]*(Popt[0][0]*SH_OPT[2]*SH_OPT[5]*SK_OPT[2] + Popt[0][1]*flowStates[0]*SH_OPT[2]*SH_OPT[4]*SK_OPT[2]);
+ K_OPT[0][1] = SK_OPT[0]*(Popt[0][0]*SH_OPT[1]*SH_OPT[5]*SK_OPT[2] + Popt[0][1]*flowStates[0]*SH_OPT[1]*SH_OPT[4]*SK_OPT[2]);
+ } else {
+ K_OPT[0][0] = 0.0f;
+ K_OPT[0][1] = 0.0f;
+ }
+ if (!inhibitGndState) {
+ K_OPT[1][0] = -SK_OPT[1]*(Popt[1][0]*SH_OPT[2]*SH_OPT[5]*SK_OPT[2] + Popt[1][1]*flowStates[0]*SH_OPT[2]*SH_OPT[4]*SK_OPT[2]);
+ K_OPT[1][1] = SK_OPT[0]*(Popt[1][0]*SH_OPT[1]*SH_OPT[5]*SK_OPT[2] + Popt[1][1]*flowStates[0]*SH_OPT[1]*SH_OPT[4]*SK_OPT[2]);
+ } else {
+ K_OPT[1][0] = 0.0f;
+ K_OPT[1][1] = 0.0f;
+ }
+
+ // calculate innovation variances
+ auxFlowObsInnovVar[0] = 1.0f/SK_OPT[1];
+ auxFlowObsInnovVar[1] = 1.0f/SK_OPT[0];
+
+ // calculate observations jacobians
+ H_OPT[0][0] = -SH025;
+ H_OPT[0][1] = -flowStates[0]*SH024;
+ H_OPT[1][0] = SH015;
+ H_OPT[1][1] = flowStates[0]*SH014;
+
+ // Check the innovation for consistency and don't fuse if > threshold
+ for (uint8_t obsIndex = 0; obsIndex < 2; obsIndex++) {
+
+ // calculate the innovation consistency test ratio
+ auxFlowTestRatio[obsIndex] = sq(auxFlowObsInnov[obsIndex]) / (sq(auxFlowInnovGate) * auxFlowObsInnovVar[obsIndex]);
+ if (auxFlowTestRatio[obsIndex] < 1.0f) {
+ // correct the state
+ for (uint8_t i = 0; i < 2 ; i++) {
+ flowStates[i] -= K_OPT[i][obsIndex] * auxFlowObsInnov[obsIndex];
+ }
+ // constrain the states
+ flowStates[0] = ConstrainFloat(flowStates[0], 0.1f, 10.0f);
+ flowStates[1] = maxf(flowStates[1], statesAtFlowTime[9] + minFlowRng);
+
+ // correct the covariance matrix
+ for (uint8_t i = 0; i < 2 ; i++) {
+ HP[i] = 0.0f;
+ for (uint8_t j = 0; j < 2 ; j++) {
+ HP[i] += H_OPT[obsIndex][j] * P[j][i];
+ }
+ }
+ for (uint8_t i = 0; i < 2 ; i++) {
+ for (uint8_t j = 0; j < 2 ; j++) {
+ nextPopt[i][j] = P[i][j] - K_OPT[i][obsIndex] * HP[j];
+ }
+ }
+
+ // prevent the state variances from becoming negative and maintain symmetry
+ Popt[0][0] = maxf(nextPopt[0][0],0.0f);
+ Popt[1][1] = maxf(nextPopt[1][1],0.0f);
+ Popt[0][1] = 0.5f * (nextPopt[0][1] + nextPopt[1][0]);
+ Popt[1][0] = Popt[0][1];
+ }
+ }
+ }
+
}
void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
@@ -2328,6 +2280,9 @@ void AttPosEKF::StoreStates(uint64_t timestamp_ms)
{
for (unsigned i=0; i<n_states; i++)
storedStates[i][storeIndex] = states[i];
+ storedOmega[0][storeIndex] = angRate.x;
+ storedOmega[1][storeIndex] = angRate.y;
+ storedOmega[2][storeIndex] = angRate.z;
statetimeStamp[storeIndex] = timestamp_ms;
storeIndex++;
if (storeIndex == data_buffer_size)
@@ -2338,16 +2293,12 @@ void AttPosEKF::ResetStoredStates()
{
// reset all stored states
memset(&storedStates[0][0], 0, sizeof(storedStates));
+ memset(&storedOmega[0][0], 0, sizeof(storedOmega));
memset(&statetimeStamp[0], 0, sizeof(statetimeStamp));
// reset store index to first
storeIndex = 0;
- // overwrite all existing states
- for (unsigned i = 0; i < n_states; i++) {
- storedStates[i][storeIndex] = states[i];
- }
-
statetimeStamp[storeIndex] = millis();
// increment to next storage index
@@ -2407,6 +2358,37 @@ int AttPosEKF::RecallStates(float* statesForFusion, uint64_t msec)
return ret;
}
+void AttPosEKF::RecallOmega(float* omegaForFusion, uint64_t msec)
+{
+ // work back in time and calculate average angular rate over the time interval
+ for (unsigned i=0; i < 3; i++) {
+ omegaForFusion[i] = 0.0f;
+ }
+ uint8_t sumIndex = 0;
+ int64_t timeDelta;
+ for (unsigned storeIndexLocal = 0; storeIndexLocal < data_buffer_size; storeIndexLocal++)
+ {
+ // calculate the average of all samples younger than msec
+ timeDelta = statetimeStamp[storeIndexLocal] - msec;
+ if (timeDelta > 0)
+ {
+ for (unsigned i=0; i < 3; i++) {
+ omegaForFusion[i] += storedOmega[i][storeIndexLocal];
+ }
+ sumIndex += 1;
+ }
+ }
+ if (sumIndex >= 1) {
+ for (unsigned i=0; i < 3; i++) {
+ omegaForFusion[i] = omegaForFusion[i] / float(sumIndex);
+ }
+ } else {
+ omegaForFusion[0] = angRate.x;
+ omegaForFusion[1] = angRate.y;
+ omegaForFusion[2] = angRate.z;
+ }
+}
+
void AttPosEKF::quat2Tnb(Mat3f &Tnb, const float (&quat)[4])
{
// Calculate the nav to body cosine matrix
@@ -2502,6 +2484,7 @@ void AttPosEKF::calcLLH(float posNED[3], double &lat, double &lon, float &hgt, d
void AttPosEKF::OnGroundCheck()
{
onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
+
if (staticMode) {
staticMode = (!refSet || (GPSstatus < GPS_FIX_3D));
}
@@ -2517,12 +2500,25 @@ void AttPosEKF::OnGroundCheck()
} else {
inhibitMagStates = false;
}
- // don't update terrain offset state if on ground
- if (onGround) {
+ // don't update terrain offset state if there is no range finder and flying at low velocity or without GPS
+ if ((onGround || !useGPS) && !useRangeFinder) {
inhibitGndState = true;
} else {
inhibitGndState = false;
}
+ // don't update terrain offset state if there is no range finder and flying at low velocity, or without GPS, as it is poorly observable
+ if ((onGround || (globalTimeStamp_ms - lastFixTime_ms) > 1000) && !useRangeFinder) {
+ inhibitGndState = true;
+ } else {
+ inhibitGndState = false;
+ }
+ // Don't update focal length offset state if there is no range finder or optical flow sensor
+ // we need both sensors to do this estimation
+ if (!useRangeFinder || !useOpticalFlow) {
+ inhibitScaleState = true;
+ } else {
+ inhibitScaleState = false;
+ }
}
void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude)
@@ -2558,7 +2554,9 @@ void AttPosEKF::CovarianceInit()
P[19][19] = sq(0.02f);
P[20][20] = P[19][19];
P[21][21] = P[19][19];
- P[22][22] = sq(0.5f);
+
+ fScaleFactorVar = 0.001f; // focal length scale factor variance
+ Popt[0][0] = 0.001f;
}
float AttPosEKF::ConstrainFloat(float val, float min_val, float max_val)
@@ -2596,7 +2594,6 @@ void AttPosEKF::ConstrainVariances()
// 14-15: Wind Vector - m/sec (North,East)
// 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
// 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)
- // 22: Terrain offset - m
// Constrain quaternion variances
for (unsigned i = 0; i <= 3; i++) {
@@ -2636,8 +2633,6 @@ void AttPosEKF::ConstrainVariances()
P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
}
- // Constrain terrain offset variance
- P[22][22] = ConstrainFloat(P[22][22], 0.0f, 10000.0f);
}
void AttPosEKF::ConstrainStates()
@@ -2655,7 +2650,6 @@ void AttPosEKF::ConstrainStates()
// 14-15: Wind Vector - m/sec (North,East)
// 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
// 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)
- // 22: Terrain offset - m
// Constrain quaternion
for (unsigned i = 0; i <= 3; i++) {
@@ -2673,7 +2667,8 @@ void AttPosEKF::ConstrainStates()
}
// Constrain altitude
- states[9] = ConstrainFloat(states[9], -4.0e4f, 1.0e4f);
+ // NOT FOR FLIGHT : Upper value of 0.0 is a temporary fix to get around lack of range finder data during development testing
+ states[9] = ConstrainFloat(states[9], -4.0e4f, 4.0e4f);
// Angle bias limit - set to 8 degrees / sec
for (unsigned i = 10; i <= 12; i++) {
@@ -2699,9 +2694,6 @@ void AttPosEKF::ConstrainStates()
states[i] = ConstrainFloat(states[i], -0.5f, 0.5f);
}
- // Constrain terrain offset
- states[22] = ConstrainFloat(states[22], -1000.0f, 1000.0f);
-
}
void AttPosEKF::ForceSymmetry()
@@ -3162,12 +3154,14 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
states[19] = magBias.x; // Magnetic Field Bias X
states[20] = magBias.y; // Magnetic Field Bias Y
states[21] = magBias.z; // Magnetic Field Bias Z
- states[22] = 0.0f; // terrain height
ResetVelocity();
ResetPosition();
ResetHeight();
+ // initialise focal length scale factor estimator states
+ flowStates[0] = 1.0f;
+
statesInitialised = true;
// initialise the covariance matrix
@@ -3223,6 +3217,9 @@ void AttPosEKF::ZeroVariables()
states[i] = 0.0f; // state matrix
}
+ // initialise the variables for the focal length scale factor to unity
+ flowStates[0] = 1.0f;
+
correctedDelAng.zero();
summedDelAng.zero();
summedDelVel.zero();
@@ -3230,12 +3227,9 @@ void AttPosEKF::ZeroVariables()
dVelIMU.zero();
lastGyroOffset.zero();
- windSpdFiltNorth = 0.0f;
- windSpdFiltEast = 0.0f;
- // setting the altitude to zero will give us a higher
- // gain to adjust faster in the first step
- windSpdFiltAltitude = 0.0f;
- windSpdFiltClimb = 0.0f;
+ // initialise states used by OpticalFlowEKF
+ flowStates[0] = 1.0f;
+ flowStates[1] = 0.0f;
for (unsigned i = 0; i < data_buffer_size; i++) {
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_22states.h
index a607955a8..b1d71bd74 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_22states.h
@@ -2,7 +2,7 @@
#include "estimator_utilities.h"
-const unsigned int n_states = 23;
+const unsigned int n_states = 22;
const unsigned int data_buffer_size = 50;
class AttPosEKF {
@@ -29,10 +29,6 @@ public:
float covDelAngMax; // maximum delta angle between covariance predictions
float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
- float a1; // optical flow sensor misalgnment angle about X axis (rad)
- float a2; // optical flow sensor misalgnment angle about Y axis (rad)
- float a3; // optical flow sensor misalgnment angle about Z axis (rad)
-
float yawVarScale;
float windVelSigma;
float dAngBiasSigma;
@@ -59,9 +55,6 @@ public:
covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
EAS2TAS = 1.0f;
- a1 = 0.0f; // optical flow sensor misalgnment angle about X axis (rad)
- a2 = 0.0f; // optical flow sensor misalgnment angle about Y axis (rad)
- a3 = 0.0f; // optical flow sensor misalgnment angle about Z axis (rad)
yawVarScale = 1.0f;
windVelSigma = 0.1f;
@@ -69,7 +62,6 @@ public:
dVelBiasSigma = 1e-4f;
magEarthSigma = 3.0e-4f;
magBodySigma = 3.0e-4f;
- gndHgtSigma = 0.02f; // assume 2% terrain gradient 1-sigma
vneSigma = 0.2f;
vdSigma = 0.3f;
@@ -82,12 +74,13 @@ public:
accelProcessNoise = 0.5f;
gndHgtSigma = 0.1f; // terrain gradient 1-sigma
- R_LOS = 0.03f; // optical flow measurement noise variance (rad/sec)^2
+ R_LOS = 0.3f; // optical flow measurement noise variance (rad/sec)^2
flowInnovGate = 3.0f; // number of standard deviations applied to the optical flow innovation consistency check
auxFlowInnovGate = 10.0f; // number of standard deviations applied to the optical flow innovation consistency check used by the auxiliary filter
- rngInnovGate = 10.0f; // number of standard deviations applied to the rnage finder innovation consistency check
- minFlowRng = 0.01f; //minimum range between ground and flow sensor
- moCompR_LOS = 0.2; // scaler from sensor gyro rate to uncertainty in LOS rate
+ rngInnovGate = 5.0f; // number of standard deviations applied to the range finder innovation consistency check
+ minFlowRng = 0.3f; //minimum range between ground and flow sensor
+ moCompR_LOS = 0.0; // scaler from sensor gyro rate to uncertainty in LOS rate
+
}
struct mag_state_struct {
@@ -134,6 +127,7 @@ public:
float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
float statesAtRngTime[n_states]; // filter states at the effective measurement time
float statesAtFlowTime[n_states]; // States at the effective optical flow measurement time
+ float omegaAcrossFlowTime[3]; // angular rates at the effective optical flow measurement time
Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
@@ -145,7 +139,7 @@ public:
Vector3f lastGyroOffset; // Last gyro offset
Vector3f delAngTotal;
- Mat3f Tbn; // transformation matrix from body to NED coordinates
+ Mat3f Tbn; // transformation matrix from body to NED coordinatesFuseOptFlow
Mat3f Tnb; // transformation amtrix from NED to body coordinates
Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
@@ -157,10 +151,6 @@ public:
float dtVelPosFilt; // average time between position / velocity fusion steps
float dtHgtFilt; // average time between height measurement updates
float dtGpsFilt; // average time between gps measurement updates
- float windSpdFiltNorth; // average wind speed north component
- float windSpdFiltEast; // average wind speed east component
- float windSpdFiltAltitude; // the last altitude used to filter wind speed
- float windSpdFiltClimb; // filtered climb rate
uint8_t fusionModeGPS; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
float innovVelPos[6]; // innovation output
float varInnovVelPos[6]; // innovation variance output
@@ -175,7 +165,8 @@ public:
float innovMag[3]; // innovation output
float varInnovMag[3]; // innovation variance output
Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
- float losData[2]; // optical flow LOS rate measurements (rad/sec)
+ float flowRadXYcomp[2]; // motion compensated optical flow angular rates(rad/sec)
+ float flowRadXY[2]; // raw (non motion compensated) optical flow angular rates (rad/sec)
float innovVtas; // innovation output
float innovRng; ///< Range finder innovation
float innovOptFlow[2]; // optical flow LOS innovations (rad/sec)
@@ -190,6 +181,8 @@ public:
bool refSet; ///< flag to indicate if the reference position has been set
Vector3f magBias; // states representing magnetometer bias vector in XYZ body axes
unsigned covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
+ uint32_t lastFixTime_ms; // Number of msec since last GPS Fix that was used
+ uint32_t globalTimeStamp_ms; // time in msec of current prediction cycle
// GPS input data variables
double gpsLat;
@@ -217,6 +210,7 @@ public:
bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
bool staticMode; ///< boolean true if no position feedback is fused
+ bool useGPS; // boolean true if GPS data is being used
bool useAirspeed; ///< boolean true if airspeed data is being used
bool useCompass; ///< boolean true if magnetometer data is being used
bool useRangeFinder; ///< true when rangefinder is being used
@@ -267,11 +261,9 @@ void FuseMagnetometer();
void FuseAirspeed();
-void FuseRangeFinder();
-
void FuseOptFlow();
-void GroundEKF();
+void OpticalFlowEKF();
void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
@@ -286,7 +278,7 @@ void StoreStates(uint64_t timestamp_ms);
* Recall the state vector.
*
* Recalls the vector stored at closest time to the one specified by msec
- *
+ *FuseOptFlow
* @return zero on success, integer indicating the number of invalid states on failure.
* Does only copy valid states, if the statesForFusion vector was initialized
* correctly by the caller, the result can be safely used, but is a mixture
@@ -295,6 +287,8 @@ void StoreStates(uint64_t timestamp_ms);
*/
int RecallStates(float *statesForFusion, uint64_t msec);
+void RecallOmega(float *omegaForFusion, uint64_t msec);
+
void ResetStoredStates();
void quat2Tbn(Mat3f &TBodyNed, const float (&quat)[4]);
@@ -325,7 +319,7 @@ void CovarianceInit();
void InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination);
-float ConstrainFloat(float val, float min, float max);
+float ConstrainFloat(float val, float min, float maxf);
void ConstrainVariances();
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 843dde978..f51962113 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -39,7 +39,7 @@ MODULE_COMMAND = ekf_att_pos_estimator
SRCS = ekf_att_pos_estimator_main.cpp \
ekf_att_pos_estimator_params.c \
- estimator_23states.cpp \
+ estimator_22states.cpp \
estimator_utilities.cpp
EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=6100
diff --git a/src/modules/land_detector/FixedwingLandDetector.cpp b/src/modules/land_detector/FixedwingLandDetector.cpp
new file mode 100644
index 000000000..8e5bcf7ba
--- /dev/null
+++ b/src/modules/land_detector/FixedwingLandDetector.cpp
@@ -0,0 +1,125 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 FixedwingLandDetector.cpp
+ * Land detection algorithm for fixedwings
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#include "FixedwingLandDetector.h"
+
+#include <cmath>
+#include <drivers/drv_hrt.h>
+
+FixedwingLandDetector::FixedwingLandDetector() : LandDetector(),
+ _paramHandle(),
+ _params(),
+ _vehicleLocalPositionSub(-1),
+ _vehicleLocalPosition({}),
+ _airspeedSub(-1),
+ _airspeed({}),
+ _parameterSub(-1),
+ _velocity_xy_filtered(0.0f),
+ _velocity_z_filtered(0.0f),
+ _airspeed_filtered(0.0f),
+ _landDetectTrigger(0)
+{
+ _paramHandle.maxVelocity = param_find("LNDFW_VEL_XY_MAX");
+ _paramHandle.maxClimbRate = param_find("LNDFW_VEL_Z_MAX");
+ _paramHandle.maxAirSpeed = param_find("LNDFW_AIRSPD_MAX");
+}
+
+void FixedwingLandDetector::initialize()
+{
+ // Subscribe to local position and airspeed data
+ _vehicleLocalPositionSub = orb_subscribe(ORB_ID(vehicle_local_position));
+ _airspeedSub = orb_subscribe(ORB_ID(airspeed));
+}
+
+void FixedwingLandDetector::updateSubscriptions()
+{
+ orb_update(ORB_ID(vehicle_local_position), _vehicleLocalPositionSub, &_vehicleLocalPosition);
+ orb_update(ORB_ID(airspeed), _airspeedSub, &_airspeed);
+}
+
+bool FixedwingLandDetector::update()
+{
+ // First poll for new data from our subscriptions
+ updateSubscriptions();
+
+ const uint64_t now = hrt_absolute_time();
+ bool landDetected = false;
+
+ // TODO: reset filtered values on arming?
+ _velocity_xy_filtered = 0.95f * _velocity_xy_filtered + 0.05f * sqrtf(_vehicleLocalPosition.vx *
+ _vehicleLocalPosition.vx + _vehicleLocalPosition.vy * _vehicleLocalPosition.vy);
+ _velocity_z_filtered = 0.95f * _velocity_z_filtered + 0.05f * fabsf(_vehicleLocalPosition.vz);
+ _airspeed_filtered = 0.95f * _airspeed_filtered + 0.05f * _airspeed.true_airspeed_m_s;
+
+ // crude land detector for fixedwing
+ if (_velocity_xy_filtered < _params.maxVelocity
+ && _velocity_z_filtered < _params.maxClimbRate
+ && _airspeed_filtered < _params.maxAirSpeed) {
+
+ // these conditions need to be stable for a period of time before we trust them
+ if (now > _landDetectTrigger) {
+ landDetected = true;
+ }
+
+ } else {
+ // reset land detect trigger
+ _landDetectTrigger = now + LAND_DETECTOR_TRIGGER_TIME;
+ }
+
+ return landDetected;
+}
+
+void FixedwingLandDetector::updateParameterCache(const bool force)
+{
+ bool updated;
+ parameter_update_s paramUpdate;
+
+ orb_check(_parameterSub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(parameter_update), _parameterSub, &paramUpdate);
+ }
+
+ if (updated || force) {
+ param_get(_paramHandle.maxVelocity, &_params.maxVelocity);
+ param_get(_paramHandle.maxClimbRate, &_params.maxClimbRate);
+ param_get(_paramHandle.maxAirSpeed, &_params.maxAirSpeed);
+ }
+}
diff --git a/src/modules/land_detector/FixedwingLandDetector.h b/src/modules/land_detector/FixedwingLandDetector.h
new file mode 100644
index 000000000..0e9c092ee
--- /dev/null
+++ b/src/modules/land_detector/FixedwingLandDetector.h
@@ -0,0 +1,105 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 FixedwingLandDetector.h
+ * Land detection algorithm for fixedwing
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#ifndef __FIXED_WING_LAND_DETECTOR_H__
+#define __FIXED_WING_LAND_DETECTOR_H__
+
+#include "LandDetector.h"
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+
+class FixedwingLandDetector : public LandDetector
+{
+public:
+ FixedwingLandDetector();
+
+protected:
+ /**
+ * @brief blocking loop, should be run in a separate thread or task. Runs at 50Hz
+ **/
+ bool update() override;
+
+ /**
+ * @brief Initializes the land detection algorithm
+ **/
+ void initialize() override;
+
+ /**
+ * @brief polls all subscriptions and pulls any data that has changed
+ **/
+ void updateSubscriptions();
+
+private:
+ /**
+ * @brief download and update local parameter cache
+ **/
+ void updateParameterCache(const bool force);
+
+ /**
+ * @brief Handles for interesting parameters
+ **/
+ struct {
+ param_t maxVelocity;
+ param_t maxClimbRate;
+ param_t maxAirSpeed;
+ } _paramHandle;
+
+ struct {
+ float maxVelocity;
+ float maxClimbRate;
+ float maxAirSpeed;
+ } _params;
+
+private:
+ int _vehicleLocalPositionSub; /**< notification of local position */
+ struct vehicle_local_position_s _vehicleLocalPosition; /**< the result from local position subscription */
+ int _airspeedSub;
+ struct airspeed_s _airspeed;
+ int _parameterSub;
+
+ float _velocity_xy_filtered;
+ float _velocity_z_filtered;
+ float _airspeed_filtered;
+ uint64_t _landDetectTrigger;
+};
+
+#endif //__FIXED_WING_LAND_DETECTOR_H__
diff --git a/src/modules/land_detector/LandDetector.cpp b/src/modules/land_detector/LandDetector.cpp
new file mode 100644
index 000000000..a4fbb9861
--- /dev/null
+++ b/src/modules/land_detector/LandDetector.cpp
@@ -0,0 +1,124 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 LandDetector.cpp
+ * Land detection algorithm
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ * @author Morten Lysgaard <morten@lysgaard.no>
+ */
+
+#include "LandDetector.h"
+#include <unistd.h> //usleep
+#include <drivers/drv_hrt.h>
+
+LandDetector::LandDetector() :
+ _landDetectedPub(-1),
+ _landDetected({0, false}),
+ _taskShouldExit(false),
+ _taskIsRunning(false)
+{
+ // ctor
+}
+
+LandDetector::~LandDetector()
+{
+ _taskShouldExit = true;
+ close(_landDetectedPub);
+}
+
+void LandDetector::shutdown()
+{
+ _taskShouldExit = true;
+}
+
+void LandDetector::start()
+{
+ // make sure this method has not already been called by another thread
+ if (isRunning()) {
+ return;
+ }
+
+ // advertise the first land detected uORB
+ _landDetected.timestamp = hrt_absolute_time();
+ _landDetected.landed = false;
+ _landDetectedPub = orb_advertise(ORB_ID(vehicle_land_detected), &_landDetected);
+
+ // initialize land detection algorithm
+ initialize();
+
+ // task is now running, keep doing so until shutdown() has been called
+ _taskIsRunning = true;
+ _taskShouldExit = false;
+
+ while (isRunning()) {
+
+ bool landDetected = update();
+
+ // publish if land detection state has changed
+ if (_landDetected.landed != landDetected) {
+ _landDetected.timestamp = hrt_absolute_time();
+ _landDetected.landed = landDetected;
+
+ // publish the land detected broadcast
+ orb_publish(ORB_ID(vehicle_land_detected), _landDetectedPub, &_landDetected);
+ }
+
+ // limit loop rate
+ usleep(1000000 / LAND_DETECTOR_UPDATE_RATE);
+ }
+
+ _taskIsRunning = false;
+ _exit(0);
+}
+
+bool LandDetector::orb_update(const struct orb_metadata *meta, int handle, void *buffer)
+{
+ bool newData = false;
+
+ // check if there is new data to grab
+ if (orb_check(handle, &newData) != OK) {
+ return false;
+ }
+
+ if (!newData) {
+ return false;
+ }
+
+ if (orb_copy(meta, handle, buffer) != OK) {
+ return false;
+ }
+
+ return true;
+}
diff --git a/src/modules/land_detector/LandDetector.h b/src/modules/land_detector/LandDetector.h
new file mode 100644
index 000000000..09db6e474
--- /dev/null
+++ b/src/modules/land_detector/LandDetector.h
@@ -0,0 +1,104 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 LandDetector.h
+ * Abstract interface for land detector algorithms
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#ifndef __LAND_DETECTOR_H__
+#define __LAND_DETECTOR_H__
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_land_detected.h>
+
+class LandDetector
+{
+public:
+
+ LandDetector();
+ virtual ~LandDetector();
+
+ /**
+ * @return true if this task is currently running
+ **/
+ inline bool isRunning() const {return _taskIsRunning;}
+
+ /**
+ * @brief Tells the Land Detector task that it should exit
+ **/
+ void shutdown();
+
+ /**
+ * @brief Blocking function that should be called from it's own task thread. This method will
+ * run the underlying algorithm at the desired update rate and publish if the landing state changes.
+ **/
+ void start();
+
+protected:
+
+ /**
+ * @brief Pure abstract method that must be overriden by sub-classes. This actually runs the underlying algorithm
+ * @return true if a landing was detected and this should be broadcast to the rest of the system
+ **/
+ virtual bool update() = 0;
+
+ /**
+ * @brief Pure abstract method that is called by this class once for initializing the uderlying algorithm (memory allocation,
+ * uORB topic subscription, creating file descriptors, etc.)
+ **/
+ virtual void initialize() = 0;
+
+ /**
+ * @brief Convinience function for polling uORB subscriptions
+ * @return true if there was new data and it was successfully copied
+ **/
+ bool orb_update(const struct orb_metadata *meta, int handle, void *buffer);
+
+ static constexpr uint32_t LAND_DETECTOR_UPDATE_RATE = 50; /**< Run algorithm at 50Hz */
+
+ static constexpr uint64_t LAND_DETECTOR_TRIGGER_TIME = 2000000; /**< usec that landing conditions have to hold
+ before triggering a land */
+
+protected:
+ orb_advert_t _landDetectedPub; /**< publisher for position in local frame */
+ struct vehicle_land_detected_s _landDetected; /**< local vehicle position */
+
+private:
+ bool _taskShouldExit; /**< true if it is requested that this task should exit */
+ bool _taskIsRunning; /**< task has reached main loop and is currently running */
+};
+
+#endif //__LAND_DETECTOR_H__
diff --git a/src/modules/land_detector/MulticopterLandDetector.cpp b/src/modules/land_detector/MulticopterLandDetector.cpp
new file mode 100644
index 000000000..277cb9363
--- /dev/null
+++ b/src/modules/land_detector/MulticopterLandDetector.cpp
@@ -0,0 +1,145 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 MulticopterLandDetector.cpp
+ * Land detection algorithm for multicopters
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ * @author Morten Lysgaard <morten@lysgaard.no>
+ */
+
+#include "MulticopterLandDetector.h"
+
+#include <cmath>
+#include <drivers/drv_hrt.h>
+
+MulticopterLandDetector::MulticopterLandDetector() : LandDetector(),
+ _paramHandle(),
+ _params(),
+ _vehicleGlobalPositionSub(-1),
+ _sensorsCombinedSub(-1),
+ _waypointSub(-1),
+ _actuatorsSub(-1),
+ _armingSub(-1),
+ _parameterSub(-1),
+ _vehicleGlobalPosition({}),
+ _sensors({}),
+ _waypoint({}),
+ _actuators({}),
+ _arming({}),
+ _landTimer(0)
+{
+ _paramHandle.maxRotation = param_find("LNDMC_Z_VEL_MAX");
+ _paramHandle.maxVelocity = param_find("LNDMC_XY_VEL_MAX");
+ _paramHandle.maxClimbRate = param_find("LNDMC_ROT_MAX");
+ _paramHandle.maxThrottle = param_find("LNDMC_THR_MAX");
+}
+
+void MulticopterLandDetector::initialize()
+{
+ // subscribe to position, attitude, arming and velocity changes
+ _vehicleGlobalPositionSub = orb_subscribe(ORB_ID(vehicle_global_position));
+ _sensorsCombinedSub = orb_subscribe(ORB_ID(sensor_combined));
+ _waypointSub = orb_subscribe(ORB_ID(position_setpoint_triplet));
+ _actuatorsSub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
+ _armingSub = orb_subscribe(ORB_ID(actuator_armed));
+ _parameterSub = orb_subscribe(ORB_ID(parameter_update));
+
+ // download parameters
+ updateParameterCache(true);
+}
+
+void MulticopterLandDetector::updateSubscriptions()
+{
+ orb_update(ORB_ID(vehicle_global_position), _vehicleGlobalPositionSub, &_vehicleGlobalPosition);
+ orb_update(ORB_ID(sensor_combined), _sensorsCombinedSub, &_sensors);
+ orb_update(ORB_ID(position_setpoint_triplet), _waypointSub, &_waypoint);
+ orb_update(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, _actuatorsSub, &_actuators);
+ orb_update(ORB_ID(actuator_armed), _armingSub, &_arming);
+}
+
+bool MulticopterLandDetector::update()
+{
+ // first poll for new data from our subscriptions
+ updateSubscriptions();
+
+ // only trigger flight conditions if we are armed
+ if (!_arming.armed) {
+ return true;
+ }
+
+ const uint64_t now = hrt_absolute_time();
+
+ // check if we are moving vertically
+ bool verticalMovement = fabsf(_vehicleGlobalPosition.vel_d) > _params.maxClimbRate;
+
+ // check if we are moving horizontally
+ bool horizontalMovement = sqrtf(_vehicleGlobalPosition.vel_n * _vehicleGlobalPosition.vel_n
+ + _vehicleGlobalPosition.vel_e * _vehicleGlobalPosition.vel_e) > _params.maxVelocity;
+
+ // next look if all rotation angles are not moving
+ bool rotating = sqrtf(_sensors.gyro_rad_s[0] * _sensors.gyro_rad_s[0] +
+ _sensors.gyro_rad_s[1] * _sensors.gyro_rad_s[1] +
+ _sensors.gyro_rad_s[2] * _sensors.gyro_rad_s[2]) > _params.maxRotation;
+
+ // check if thrust output is minimal (about half of default)
+ bool minimalThrust = _actuators.control[3] <= _params.maxThrottle;
+
+ if (verticalMovement || rotating || !minimalThrust || horizontalMovement) {
+ // sensed movement, so reset the land detector
+ _landTimer = now;
+ return false;
+ }
+
+ return now - _landTimer > LAND_DETECTOR_TRIGGER_TIME;
+}
+
+void MulticopterLandDetector::updateParameterCache(const bool force)
+{
+ bool updated;
+ parameter_update_s paramUpdate;
+
+ orb_check(_parameterSub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(parameter_update), _parameterSub, &paramUpdate);
+ }
+
+ if (updated || force) {
+ param_get(_paramHandle.maxClimbRate, &_params.maxClimbRate);
+ param_get(_paramHandle.maxVelocity, &_params.maxVelocity);
+ param_get(_paramHandle.maxRotation, &_params.maxRotation);
+ param_get(_paramHandle.maxThrottle, &_params.maxThrottle);
+ }
+}
diff --git a/src/modules/land_detector/MulticopterLandDetector.h b/src/modules/land_detector/MulticopterLandDetector.h
new file mode 100644
index 000000000..7bb7f1a90
--- /dev/null
+++ b/src/modules/land_detector/MulticopterLandDetector.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 MulticopterLandDetector.h
+ * Land detection algorithm for multicopters
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ * @author Morten Lysgaard <morten@lysgaard.no>
+ */
+
+#ifndef __MULTICOPTER_LAND_DETECTOR_H__
+#define __MULTICOPTER_LAND_DETECTOR_H__
+
+#include "LandDetector.h"
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+
+class MulticopterLandDetector : public LandDetector
+{
+public:
+ MulticopterLandDetector();
+
+protected:
+ /**
+ * @brief polls all subscriptions and pulls any data that has changed
+ **/
+ void updateSubscriptions();
+
+ /**
+ * @brief Runs one iteration of the land detection algorithm
+ **/
+ bool update() override;
+
+ /**
+ * @brief Initializes the land detection algorithm
+ **/
+ void initialize() override;
+
+
+private:
+ /**
+ * @brief download and update local parameter cache
+ **/
+ void updateParameterCache(const bool force);
+
+ /**
+ * @brief Handles for interesting parameters
+ **/
+ struct {
+ param_t maxClimbRate;
+ param_t maxVelocity;
+ param_t maxRotation;
+ param_t maxThrottle;
+ } _paramHandle;
+
+ struct {
+ float maxClimbRate;
+ float maxVelocity;
+ float maxRotation;
+ float maxThrottle;
+ } _params;
+
+private:
+ int _vehicleGlobalPositionSub; /**< notification of global position */
+ int _sensorsCombinedSub;
+ int _waypointSub;
+ int _actuatorsSub;
+ int _armingSub;
+ int _parameterSub;
+
+ struct vehicle_global_position_s _vehicleGlobalPosition; /**< the result from global position subscription */
+ struct sensor_combined_s _sensors; /**< subscribe to sensor readings */
+ struct position_setpoint_triplet_s _waypoint; /**< subscribe to autopilot navigation */
+ struct actuator_controls_s _actuators;
+ struct actuator_armed_s _arming;
+
+ uint64_t _landTimer; /**< timestamp in microseconds since a possible land was detected*/
+};
+
+#endif //__MULTICOPTER_LAND_DETECTOR_H__
diff --git a/src/modules/land_detector/land_detector_main.cpp b/src/modules/land_detector/land_detector_main.cpp
new file mode 100644
index 000000000..1e43e7ad5
--- /dev/null
+++ b/src/modules/land_detector/land_detector_main.cpp
@@ -0,0 +1,214 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 land_detector_main.cpp
+ * Land detection algorithm
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#include <unistd.h> //usleep
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <drivers/drv_hrt.h>
+#include <systemlib/systemlib.h> //Scheduler
+#include <systemlib/err.h> //print to console
+
+#include "FixedwingLandDetector.h"
+#include "MulticopterLandDetector.h"
+
+//Function prototypes
+static int land_detector_start(const char *mode);
+static void land_detector_stop();
+
+/**
+ * land detector app start / stop handling function
+ * This makes the land detector module accessible from the nuttx shell
+ * @ingroup apps
+ */
+extern "C" __EXPORT int land_detector_main(int argc, char *argv[]);
+
+//Private variables
+static LandDetector *land_detector_task = nullptr;
+static int _landDetectorTaskID = -1;
+static char _currentMode[12];
+
+/**
+* Deamon thread function
+**/
+static void land_detector_deamon_thread(int argc, char *argv[])
+{
+ land_detector_task->start();
+}
+
+/**
+* Stop the task, force killing it if it doesn't stop by itself
+**/
+static void land_detector_stop()
+{
+ if (land_detector_task == nullptr || _landDetectorTaskID == -1) {
+ errx(1, "not running");
+ return;
+ }
+
+ land_detector_task->shutdown();
+
+ //Wait for task to die
+ int i = 0;
+
+ do {
+ /* wait 20ms */
+ usleep(20000);
+
+ /* if we have given up, kill it */
+ if (++i > 50) {
+ task_delete(_landDetectorTaskID);
+ break;
+ }
+ } while (land_detector_task->isRunning());
+
+
+ delete land_detector_task;
+ land_detector_task = nullptr;
+ _landDetectorTaskID = -1;
+ errx(0, "land_detector has been stopped");
+}
+
+/**
+* Start new task, fails if it is already running. Returns OK if successful
+**/
+static int land_detector_start(const char *mode)
+{
+ if (land_detector_task != nullptr || _landDetectorTaskID != -1) {
+ errx(1, "already running");
+ return -1;
+ }
+
+ //Allocate memory
+ if (!strcmp(mode, "fixedwing")) {
+ land_detector_task = new FixedwingLandDetector();
+
+ } else if (!strcmp(mode, "multicopter")) {
+ land_detector_task = new MulticopterLandDetector();
+
+ } else {
+ errx(1, "[mode] must be either 'fixedwing' or 'multicopter'");
+ return -1;
+ }
+
+ //Check if alloc worked
+ if (land_detector_task == nullptr) {
+ errx(1, "alloc failed");
+ return -1;
+ }
+
+ //Start new thread task
+ _landDetectorTaskID = task_spawn_cmd("land_detector",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_DEFAULT,
+ 1200,
+ (main_t)&land_detector_deamon_thread,
+ nullptr);
+
+ if (_landDetectorTaskID < 0) {
+ errx(1, "task start failed: %d", -errno);
+ return -1;
+ }
+
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ const uint32_t timeout = hrt_absolute_time() + 5000000; //5 second timeout
+
+ while (!land_detector_task->isRunning()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+
+ if (hrt_absolute_time() > timeout) {
+ err(1, "start failed - timeout");
+ land_detector_stop();
+ exit(1);
+ }
+ }
+
+ printf("\n");
+
+ //Remember current active mode
+ strncpy(_currentMode, mode, 12);
+
+ exit(0);
+ return 0;
+}
+
+/**
+* Main entry point for this module
+**/
+int land_detector_main(int argc, char *argv[])
+{
+
+ if (argc < 1) {
+ warnx("usage: land_detector {start|stop|status} [mode]\nmode can either be 'fixedwing' or 'multicopter'");
+ exit(0);
+ }
+
+ if (argc >= 2 && !strcmp(argv[1], "start")) {
+ land_detector_start(argv[2]);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ land_detector_stop();
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (land_detector_task) {
+
+ if (land_detector_task->isRunning()) {
+ warnx("running (%s)", _currentMode);
+
+ } else {
+ errx(1, "exists, but not running (%s)", _currentMode);
+ }
+
+ exit(0);
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warn("usage: land_detector {start|stop|status} [mode]\nmode can either be 'fixedwing' or 'multicopter'");
+ return 1;
+}
diff --git a/src/modules/land_detector/land_detector_params.c b/src/modules/land_detector/land_detector_params.c
new file mode 100644
index 000000000..0302bc7c1
--- /dev/null
+++ b/src/modules/land_detector/land_detector_params.c
@@ -0,0 +1,104 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014, 2015 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 land_detector.c
+ * Land detector algorithm parameters.
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#include <systemlib/param/param.h>
+
+/**
+ * Multicopter max climb rate
+ *
+ * Maximum vertical velocity allowed to trigger a land (m/s up and down)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDMC_Z_VEL_MAX, 0.30f);
+
+/**
+ * Multicopter max horizontal velocity
+ *
+ * Maximum horizontal velocity allowed to trigger a land (m/s)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDMC_XY_VEL_MAX, 1.00f);
+
+/**
+ * Multicopter max rotation
+ *
+ * Maximum allowed around each axis to trigger a land (radians per second)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDMC_ROT_MAX, 0.20f);
+
+/**
+ * Multicopter max throttle
+ *
+ * Maximum actuator output on throttle before triggering a land
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDMC_THR_MAX, 0.20f);
+
+/**
+ * Fixedwing max horizontal velocity
+ *
+ * Maximum horizontal velocity allowed to trigger a land (m/s)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDFW_VEL_XY_MAX, 0.20f);
+
+/**
+ * Fixedwing max climb rate
+ *
+ * Maximum vertical velocity allowed to trigger a land (m/s up and down)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDFW_VEL_Z_MAX, 10.00f);
+
+/**
+ * Airspeed max
+ *
+ * Maximum airspeed allowed to trigger a land (m/s)
+ *
+ * @group Land Detector
+ */
+PARAM_DEFINE_FLOAT(LNDFW_AIRSPD_MAX, 10.00f);
diff --git a/src/modules/land_detector/module.mk b/src/modules/land_detector/module.mk
new file mode 100644
index 000000000..e08a4b7a8
--- /dev/null
+++ b/src/modules/land_detector/module.mk
@@ -0,0 +1,13 @@
+#
+# Land detector
+#
+
+MODULE_COMMAND = land_detector
+
+SRCS = land_detector_main.cpp \
+ land_detector_params.c \
+ LandDetector.cpp \
+ MulticopterLandDetector.cpp \
+ FixedwingLandDetector.cpp
+
+EXTRACXXFLAGS = -Weffc++ -Os
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index ce3f2ae0e..f4e3dc441 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -92,6 +92,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_mavlink(parent),
status{},
hil_local_pos{},
+ hil_land_detector{},
_control_mode{},
_global_pos_pub(-1),
_local_pos_pub(-1),
@@ -118,6 +119,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
+ _land_detector_pub(-1),
_control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))),
_hil_frames(0),
_old_timestamp(0),
@@ -1353,9 +1355,6 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
hil_local_pos.xy_global = true;
hil_local_pos.z_global = true;
- bool landed = (float)(hil_state.alt) / 1000.0f < (_hil_local_alt0 + 0.1f); // XXX improve?
- hil_local_pos.landed = landed;
-
if (_local_pos_pub < 0) {
_local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &hil_local_pos);
@@ -1364,6 +1363,22 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg)
}
}
+ /* land detector */
+ {
+ bool landed = (float)(hil_state.alt) / 1000.0f < (_hil_local_alt0 + 0.1f); // XXX improve?
+ if(hil_land_detector.landed != landed) {
+ hil_land_detector.landed = landed;
+ hil_land_detector.timestamp = hrt_absolute_time();
+
+ if (_land_detector_pub < 0) {
+ _land_detector_pub = orb_advertise(ORB_ID(vehicle_land_detected), &hil_land_detector);
+
+ } else {
+ orb_publish(ORB_ID(vehicle_land_detected), _land_detector_pub, &hil_land_detector);
+ }
+ }
+ }
+
/* accelerometer */
{
struct accel_report accel;
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 4afc9b372..699996860 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -50,6 +50,7 @@
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_land_detected.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/offboard_control_setpoint.h>
@@ -145,6 +146,7 @@ private:
mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos;
+ struct vehicle_land_detected_s hil_land_detector;
struct vehicle_control_mode_s _control_mode;
orb_advert_t _global_pos_pub;
orb_advert_t _local_pos_pub;
@@ -171,6 +173,7 @@ private:
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
+ orb_advert_t _land_detector_pub;
int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;
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 38011a935..68ebd0f4f 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -247,9 +247,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float baro_offset = 0.0f; // baro offset for reference altitude, initialized on start, then adjusted
float surface_offset = 0.0f; // ground level offset from reference altitude
float surface_offset_rate = 0.0f; // surface offset change rate
- float alt_avg = 0.0f;
- bool landed = true;
- hrt_abstime landed_time = 0;
hrt_abstime accel_timestamp = 0;
hrt_abstime baro_timestamp = 0;
@@ -1069,36 +1066,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
inertial_filter_correct(-y_est[1], dt, y_est, 1, params.w_xy_res_v);
}
- /* detect land */
- alt_avg += (- z_est[0] - alt_avg) * dt / params.land_t;
- float alt_disp2 = - z_est[0] - alt_avg;
- alt_disp2 = alt_disp2 * alt_disp2;
- float land_disp2 = params.land_disp * params.land_disp;
- /* get actual thrust output */
- float thrust = armed.armed ? actuator.control[3] : 0.0f;
-
- if (landed) {
- if (alt_disp2 > land_disp2 || thrust > params.land_thr) {
- landed = false;
- landed_time = 0;
- }
- } else {
- if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
- if (landed_time == 0) {
- landed_time = t; // land detected first time
-
- } else {
- if (t > landed_time + params.land_t * 1000000.0f) {
- landed = true;
- landed_time = 0;
- }
- }
-
- } else {
- landed_time = 0;
- }
- }
-
if (verbose_mode) {
/* print updates rate */
if (t > updates_counter_start + updates_counter_len) {
@@ -1149,7 +1116,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.vy = y_est[1];
local_pos.z = z_est[0];
local_pos.vz = z_est[1];
- local_pos.landed = landed;
local_pos.yaw = att.yaw;
local_pos.dist_bottom_valid = dist_bottom_valid;
local_pos.eph = eph;
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 58c9429b6..d20f776d6 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -454,6 +454,10 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
{
bool result = false;
+ if (!(num_values) || !(values) || !(frame_len)) {
+ return result;
+ }
+
/* avoid racing with PPM updates */
irqstate_t state = irqsave();
@@ -468,7 +472,7 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
if (*num_values > PX4IO_RC_INPUT_CHANNELS)
*num_values = PX4IO_RC_INPUT_CHANNELS;
- for (unsigned i = 0; i < *num_values; i++) {
+ for (unsigned i = 0; ((i < *num_values) && (i < PPM_MAX_CHANNELS)); i++) {
values[i] = ppm_buffer[i];
}
@@ -476,8 +480,7 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
ppm_last_valid_decode = 0;
/* store PPM frame length */
- if (num_values)
- *frame_len = ppm_frame_length;
+ *frame_len = ppm_frame_length;
/* good if we got any channels */
result = (*num_values > 0);
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index d35b70239..a3407e42c 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -94,6 +94,7 @@
#include <uORB/topics/servorail_status.h>
#include <uORB/topics/wind_estimate.h>
#include <uORB/topics/encoders.h>
+#include <uORB/topics/vtol_vehicle_status.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -1000,6 +1001,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct satellite_info_s sat_info;
struct wind_estimate_s wind_estimate;
struct encoders_s encoders;
+ struct vtol_vehicle_status_s vtol_status;
} buf;
memset(&buf, 0, sizeof(buf));
@@ -1019,6 +1021,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GPS_s log_GPS;
struct log_ATTC_s log_ATTC;
struct log_STAT_s log_STAT;
+ struct log_VTOL_s log_VTOL;
struct log_RC_s log_RC;
struct log_OUT0_s log_OUT0;
struct log_AIRS_s log_AIRS;
@@ -1053,6 +1056,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct {
int cmd_sub;
int status_sub;
+ int vtol_status_sub;
int sensor_sub;
int att_sub;
int att_sp_sub;
@@ -1086,6 +1090,7 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ subs.vtol_status_sub = orb_subscribe(ORB_ID(vtol_vehicle_status));
subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
@@ -1112,6 +1117,7 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.system_power_sub = orb_subscribe(ORB_ID(system_power));
subs.servorail_status_sub = orb_subscribe(ORB_ID(servorail_status));
subs.wind_sub = orb_subscribe(ORB_ID(wind_estimate));
+
/* we need to rate-limit wind, as we do not need the full update rate */
orb_set_interval(subs.wind_sub, 90);
subs.encoders_sub = orb_subscribe(ORB_ID(encoders));
@@ -1218,6 +1224,13 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(STAT);
}
+ /* --- VTOL VEHICLE STATUS --- */
+ if(copy_if_updated(ORB_ID(vtol_vehicle_status), subs.vtol_status_sub, &buf.vtol_status)) {
+ log_msg.msg_type = LOG_VTOL_MSG;
+ log_msg.body.log_VTOL.airspeed_tot = buf.vtol_status.airspeed_tot;
+ LOGBUFFER_WRITE_AND_COUNT(VTOL);
+ }
+
/* --- GPS POSITION - UNIT #1 --- */
if (gps_pos_updated) {
@@ -1424,6 +1437,10 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- ATTITUDE --- */
if (copy_if_updated(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att)) {
log_msg.msg_type = LOG_ATT_MSG;
+ log_msg.body.log_ATT.q_w = buf.att.q[0];
+ log_msg.body.log_ATT.q_x = buf.att.q[1];
+ log_msg.body.log_ATT.q_y = buf.att.q[2];
+ log_msg.body.log_ATT.q_z = buf.att.q[3];
log_msg.body.log_ATT.roll = buf.att.roll;
log_msg.body.log_ATT.pitch = buf.att.pitch;
log_msg.body.log_ATT.yaw = buf.att.yaw;
@@ -1434,18 +1451,6 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_ATT.gy = buf.att.g_comp[1];
log_msg.body.log_ATT.gz = buf.att.g_comp[2];
LOGBUFFER_WRITE_AND_COUNT(ATT);
- // secondary attitude
- log_msg.msg_type = LOG_ATT2_MSG;
- log_msg.body.log_ATT.roll = buf.att.roll_sec;
- log_msg.body.log_ATT.pitch = buf.att.pitch_sec;
- log_msg.body.log_ATT.yaw = buf.att.yaw_sec;
- log_msg.body.log_ATT.roll_rate = buf.att.rollspeed_sec;
- log_msg.body.log_ATT.pitch_rate = buf.att.pitchspeed_sec;
- log_msg.body.log_ATT.yaw_rate = buf.att.yawspeed_sec;
- log_msg.body.log_ATT.gx = buf.att.g_comp_sec[0];
- log_msg.body.log_ATT.gy = buf.att.g_comp_sec[1];
- log_msg.body.log_ATT.gz = buf.att.g_comp_sec[2];
- LOGBUFFER_WRITE_AND_COUNT(ATT);
}
/* --- ATTITUDE SETPOINT --- */
@@ -1514,7 +1519,6 @@ int sdlog2_thread_main(int argc, char *argv[])
(buf.local_pos.v_z_valid ? 8 : 0) |
(buf.local_pos.xy_global ? 16 : 0) |
(buf.local_pos.z_global ? 32 : 0);
- log_msg.body.log_LPOS.landed = buf.local_pos.landed;
log_msg.body.log_LPOS.ground_dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
log_msg.body.log_LPOS.eph = buf.local_pos.eph;
log_msg.body.log_LPOS.epv = buf.local_pos.epv;
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 5941bfac0..7080d9c31 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -50,8 +50,11 @@
#pragma pack(push, 1)
/* --- ATT - ATTITUDE --- */
#define LOG_ATT_MSG 2
-#define LOG_ATT2_MSG 41
struct log_ATT_s {
+ float q_w;
+ float q_x;
+ float q_y;
+ float q_z;
float roll;
float pitch;
float yaw;
@@ -113,7 +116,6 @@ struct log_LPOS_s {
int32_t ref_lon;
float ref_alt;
uint8_t pos_flags;
- uint8_t landed;
uint8_t ground_dist_flags;
float eph;
float epv;
@@ -427,6 +429,12 @@ struct log_ENCD_s {
/* --- AIR SPEED SENSORS - DIFF. PRESSURE --- */
#define LOG_AIR1_MSG 40
+/* --- VTOL - VTOL VEHICLE STATUS */
+#define LOG_VTOL_MSG 42
+struct log_VTOL_s {
+ float airspeed_tot;
+};
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -455,19 +463,20 @@ struct log_PARM_s {
static const struct log_format_s log_formats[] = {
/* business-level messages, ID < 0x80 */
LOG_FORMAT_S(ATT, ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
- LOG_FORMAT_S(ATT2, ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
+ LOG_FORMAT(ATT, "fffffffffffff", "qw,qx,qy,qz,Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"),
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT_S(IMU, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT_S(IMU1, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT_S(SENS, SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
LOG_FORMAT_S(AIR1, SENS, "fffff", "BaroPa,BaroAlt,BaroTmp,DiffPres,DiffPresF"),
- LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
+ LOG_FORMAT(LPOS, "ffffffffLLfBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"),
LOG_FORMAT_S(ATTC, ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT_S(ATC1, ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT(STAT, "BBBfBB", "MainState,ArmState,FailsafeState,BatRem,BatWarn,Landed"),
+ LOG_FORMAT(VTOL, "f", "Arsp"),
LOG_FORMAT(RC, "ffffffffBB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost"),
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index a065541b9..bf5708e0b 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -98,6 +98,12 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f);
*/
PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f);
+/**
+ * ID of Magnetometer the calibration is for.
+ *
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_INT32(SENS_MAG_ID, 0);
/**
* Magnetometer X-axis offset
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 0a27367d9..6aa6b6bbd 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-2015 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
@@ -1465,7 +1465,7 @@ Sensors::parameter_update_poll(bool forced)
/* this sensor is optional, abort without error */
- if (fd > 0) {
+ if (fd >= 0) {
struct airspeed_scale airscale = {
_parameters.diff_pres_offset_pa,
1.0f,
diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c
index 998b5ac7d..a1a8e7ea8 100644
--- a/src/modules/systemlib/err.c
+++ b/src/modules/systemlib/err.c
@@ -154,6 +154,7 @@ warn(const char *fmt, ...)
va_start(args, fmt);
vwarn(fmt, args);
+ va_end(args);
}
void
@@ -169,6 +170,7 @@ warnc(int errcode, const char *fmt, ...)
va_start(args, fmt);
vwarnc(errcode, fmt, args);
+ va_end(args);
}
void
@@ -184,6 +186,7 @@ warnx(const char *fmt, ...)
va_start(args, fmt);
vwarnx(fmt, args);
+ va_end(args);
}
void
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 293412455..78fdf4de7 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -83,6 +83,9 @@ ORB_DEFINE(sensor_combined, struct sensor_combined_s);
#include "topics/vehicle_gps_position.h"
ORB_DEFINE(vehicle_gps_position, struct vehicle_gps_position_s);
+#include "topics/vehicle_land_detected.h"
+ORB_DEFINE(vehicle_land_detected, struct vehicle_land_detected_s);
+
#include "topics/satellite_info.h"
ORB_DEFINE(satellite_info, struct satellite_info_s);
diff --git a/src/modules/uORB/topics/vehicle_land_detected.h b/src/modules/uORB/topics/vehicle_land_detected.h
new file mode 100644
index 000000000..51b3568e8
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_land_detected.h
@@ -0,0 +1,63 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013-2015 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 vehicle_land_detected.h
+ * Land detected uORB topic
+ *
+ * @author Johan Jansen <jnsn.johan@gmail.com>
+ */
+
+#ifndef __TOPIC_VEHICLE_LANDED_H__
+#define __TOPIC_VEHICLE_LANDED_H__
+
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct vehicle_land_detected_s {
+ uint64_t timestamp; /**< timestamp of the setpoint */
+ bool landed; /**< true if vehicle is currently landed on the ground*/
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_land_detected);
+
+#endif //__TOPIC_VEHICLE_LANDED_H__
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index 5d39c897d..8b46c5a3f 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -77,7 +77,6 @@ struct vehicle_local_position_s {
double ref_lat; /**< Reference point latitude in degrees */
double ref_lon; /**< Reference point longitude in degrees */
float ref_alt; /**< Reference altitude AMSL in meters, MUST be set to current (not at reference point!) ground level */
- bool landed; /**< true if vehicle is landed */
/* Distance to surface */
float dist_bottom; /**< Distance to bottom surface (ground) */
float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
diff --git a/src/modules/uORB/topics/vtol_vehicle_status.h b/src/modules/uORB/topics/vtol_vehicle_status.h
index 7b4e22bc8..968c2b6bd 100644
--- a/src/modules/uORB/topics/vtol_vehicle_status.h
+++ b/src/modules/uORB/topics/vtol_vehicle_status.h
@@ -55,6 +55,7 @@ struct vtol_vehicle_status_s {
uint64_t timestamp; /**< Microseconds since system boot */
bool vtol_in_rw_mode; /*true: vtol vehicle is in rotating wing mode */
bool fw_permanent_stab; /**< In fw mode stabilize attitude even if in manual mode*/
+ float airspeed_tot; /*< Estimated airspeed over control surfaces */
};
/**
diff --git a/src/modules/uORB/uORB.cpp b/src/modules/uORB/uORB.cpp
index 149b8f6d2..3373aac83 100644
--- a/src/modules/uORB/uORB.cpp
+++ b/src/modules/uORB/uORB.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (Cc) 2012-2015 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
@@ -230,7 +230,7 @@ ORBDevNode::open(struct file *filp)
ret = CDev::open(filp);
if (ret != OK)
- free(sd);
+ delete sd;
return ret;
}
@@ -817,18 +817,6 @@ uorb_main(int argc, char *argv[])
namespace
{
-void debug(const char *fmt, ...)
-{
- va_list ap;
-
- va_start(ap, fmt);
- vfprintf(stderr, fmt, ap);
- va_end(ap);
- fprintf(stderr, "\n");
- fflush(stderr);
- usleep(100000);
-}
-
/**
* Advertise a node; don't consider it an error if the node has
* already been advertised.
diff --git a/src/modules/vtol_att_control/vtol_att_control_main.cpp b/src/modules/vtol_att_control/vtol_att_control_main.cpp
index c72a85ecd..8e68730b8 100644
--- a/src/modules/vtol_att_control/vtol_att_control_main.cpp
+++ b/src/modules/vtol_att_control/vtol_att_control_main.cpp
@@ -65,6 +65,8 @@
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/airspeed.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/battery_status.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
@@ -105,7 +107,9 @@ private:
int _params_sub; //parameter updates subscription
int _manual_control_sp_sub; //manual control setpoint subscription
int _armed_sub; //arming status subscription
+ int _local_pos_sub; // sensor subscription
int _airspeed_sub; // airspeed subscription
+ int _battery_status_sub; // battery status subscription
int _actuator_inputs_mc; //topic on which the mc_att_controller publishes actuator inputs
int _actuator_inputs_fw; //topic on which the fw_att_controller publishes actuator inputs
@@ -129,7 +133,9 @@ private:
struct actuator_controls_s _actuators_mc_in; //actuator controls from mc_att_control
struct actuator_controls_s _actuators_fw_in; //actuator controls from fw_att_control
struct actuator_armed_s _armed; //actuator arming status
+ struct vehicle_local_position_s _local_pos;
struct airspeed_s _airspeed; // airspeed
+ struct battery_status_s _batt_status; // battery status
struct {
param_t idle_pwm_mc; //pwm value for idle in mc mode
@@ -139,6 +145,9 @@ private:
float mc_airspeed_trim; // trim airspeed in multicopter mode
float mc_airspeed_max; // max airpseed in multicopter mode
float fw_pitch_trim; // trim for neutral elevon position in fw mode
+ float power_max; // maximum power of one engine
+ float prop_eff; // factor to calculate prop efficiency
+ float arsp_lp_gain; // total airspeed estimate low pass gain
} _params;
struct {
@@ -149,6 +158,9 @@ private:
param_t mc_airspeed_trim;
param_t mc_airspeed_max;
param_t fw_pitch_trim;
+ param_t power_max;
+ param_t prop_eff;
+ param_t arsp_lp_gain;
} _params_handles;
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -159,6 +171,7 @@ private:
* to waste energy when gliding. */
bool flag_idle_mc; //false = "idle is set for fixed wing mode"; true = "idle is set for multicopter mode"
unsigned _motor_count; // number of motors
+ float _airspeed_tot;
//*****************Member functions***********************************************************************
@@ -172,7 +185,9 @@ private:
void actuator_controls_fw_poll(); //Check for changes in fw_attitude_control output
void vehicle_rates_sp_mc_poll();
void vehicle_rates_sp_fw_poll();
+ void vehicle_local_pos_poll(); // Check for changes in sensor values
void vehicle_airspeed_poll(); // Check for changes in airspeed
+ void vehicle_battery_poll(); // Check for battery updates
void parameters_update_poll(); //Check if parameters have changed
int parameters_update(); //Update local paraemter cache
void fill_mc_att_control_output(); //write mc_att_control results to actuator message
@@ -182,6 +197,7 @@ private:
void set_idle_fw();
void set_idle_mc();
void scale_mc_output();
+ void calc_tot_airspeed(); // estimated airspeed seen by elevons
};
namespace VTOL_att_control
@@ -205,7 +221,9 @@ VtolAttitudeControl::VtolAttitudeControl() :
_params_sub(-1),
_manual_control_sp_sub(-1),
_armed_sub(-1),
+ _local_pos_sub(-1),
_airspeed_sub(-1),
+ _battery_status_sub(-1),
//init publication handlers
_actuators_0_pub(-1),
@@ -218,6 +236,7 @@ VtolAttitudeControl::VtolAttitudeControl() :
{
flag_idle_mc = true;
+ _airspeed_tot = 0.0f;
memset(& _vtol_vehicle_status, 0, sizeof(_vtol_vehicle_status));
_vtol_vehicle_status.vtol_in_rw_mode = true; /* start vtol in rotary wing mode*/
@@ -234,7 +253,9 @@ VtolAttitudeControl::VtolAttitudeControl() :
memset(&_actuators_mc_in, 0, sizeof(_actuators_mc_in));
memset(&_actuators_fw_in, 0, sizeof(_actuators_fw_in));
memset(&_armed, 0, sizeof(_armed));
+ memset(&_local_pos,0,sizeof(_local_pos));
memset(&_airspeed,0,sizeof(_airspeed));
+ memset(&_batt_status,0,sizeof(_batt_status));
_params.idle_pwm_mc = PWM_LOWEST_MIN;
_params.vtol_motor_count = 0;
@@ -247,6 +268,9 @@ VtolAttitudeControl::VtolAttitudeControl() :
_params_handles.mc_airspeed_max = param_find("VT_MC_ARSPD_MAX");
_params_handles.mc_airspeed_trim = param_find("VT_MC_ARSPD_TRIM");
_params_handles.fw_pitch_trim = param_find("VT_FW_PITCH_TRIM");
+ _params_handles.power_max = param_find("VT_POWER_MAX");
+ _params_handles.prop_eff = param_find("VT_PROP_EFF");
+ _params_handles.arsp_lp_gain = param_find("VT_ARSP_LP_GAIN");
/* fetch initial parameter values */
parameters_update();
@@ -388,6 +412,19 @@ VtolAttitudeControl::vehicle_airspeed_poll() {
}
/**
+* Check for battery updates.
+*/
+void
+VtolAttitudeControl::vehicle_battery_poll() {
+ bool updated;
+ orb_check(_battery_status_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(battery_status), _battery_status_sub , &_batt_status);
+ }
+}
+
+/**
* Check for parameter updates.
*/
void
@@ -406,6 +443,22 @@ VtolAttitudeControl::parameters_update_poll()
}
/**
+* Check for sensor updates.
+*/
+void
+VtolAttitudeControl::vehicle_local_pos_poll()
+{
+ bool updated;
+ /* Check if parameters have changed */
+ orb_check(_local_pos_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_local_position), _local_pos_sub , &_local_pos);
+ }
+
+}
+
+/**
* Update parameters.
*/
int
@@ -437,6 +490,18 @@ VtolAttitudeControl::parameters_update()
param_get(_params_handles.fw_pitch_trim, &v);
_params.fw_pitch_trim = v;
+ /* vtol maximum power engine can produce */
+ param_get(_params_handles.power_max, &v);
+ _params.power_max = v;
+
+ /* vtol propeller efficiency factor */
+ param_get(_params_handles.prop_eff, &v);
+ _params.prop_eff = v;
+
+ /* vtol total airspeed estimate low pass gain */
+ param_get(_params_handles.arsp_lp_gain, &v);
+ _params.arsp_lp_gain = v;
+
return OK;
}
@@ -555,7 +620,7 @@ void
VtolAttitudeControl::scale_mc_output() {
// scale around tuning airspeed
float airspeed;
-
+ calc_tot_airspeed(); // estimate air velocity seen by elevons
// if airspeed is not updating, we assume the normal average speed
if (bool nonfinite = !isfinite(_airspeed.true_airspeed_m_s) ||
hrt_elapsed_time(&_airspeed.timestamp) > 1e6) {
@@ -563,16 +628,12 @@ VtolAttitudeControl::scale_mc_output() {
if (nonfinite) {
perf_count(_nonfinite_input_perf);
}
- } else {
- // prevent numerical drama by requiring 0.5 m/s minimal speed
- airspeed = math::max(0.5f, _airspeed.true_airspeed_m_s);
- }
-
- // Sanity check if airspeed is consistent with throttle
- if(_manual_control_sp.z >= 0.35f && airspeed < _params.mc_airspeed_trim) { // XXX magic number, should be hover throttle param
- airspeed = _params.mc_airspeed_trim;
+ } else {
+ airspeed = _airspeed_tot;
+ airspeed = math::constrain(airspeed,_params.mc_airspeed_min, _params.mc_airspeed_max);
}
+ _vtol_vehicle_status.airspeed_tot = airspeed; // save value for logging
/*
* For scaling our actuators using anything less than the min (close to stall)
* speed doesn't make any sense - its the strongest reasonable deflection we
@@ -584,6 +645,23 @@ VtolAttitudeControl::scale_mc_output() {
_actuators_mc_in.control[1] = math::constrain(_actuators_mc_in.control[1]*airspeed_scaling*airspeed_scaling,-1.0f,1.0f);
}
+void VtolAttitudeControl::calc_tot_airspeed() {
+ float airspeed = math::max(1.0f, _airspeed.true_airspeed_m_s); // prevent numerical drama
+ // calculate momentary power of one engine
+ float P = _batt_status.voltage_filtered_v * _batt_status.current_a / _params.vtol_motor_count;
+ P = math::constrain(P,1.0f,_params.power_max);
+ // calculate prop efficiency
+ float power_factor = 1.0f - P*_params.prop_eff/_params.power_max;
+ float eta = (1.0f/(1 + expf(-0.4f * power_factor * airspeed)) - 0.5f)*2.0f;
+ eta = math::constrain(eta,0.001f,1.0f); // live on the safe side
+ // calculate induced airspeed by propeller
+ float v_ind = (airspeed/eta - airspeed)*2.0f;
+ // calculate total airspeed
+ float airspeed_raw = airspeed + v_ind;
+ // apply low-pass filter
+ _airspeed_tot = _params.arsp_lp_gain * (_airspeed_tot - airspeed_raw) + airspeed_raw;
+}
+
void
VtolAttitudeControl::task_main_trampoline(int argc, char *argv[])
{
@@ -604,7 +682,9 @@ void VtolAttitudeControl::task_main()
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
+ _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _battery_status_sub = orb_subscribe(ORB_ID(battery_status));
_actuator_inputs_mc = orb_subscribe(ORB_ID(actuator_controls_virtual_mc));
_actuator_inputs_fw = orb_subscribe(ORB_ID(actuator_controls_virtual_fw));
@@ -674,7 +754,10 @@ void VtolAttitudeControl::task_main()
vehicle_rates_sp_mc_poll();
vehicle_rates_sp_fw_poll();
parameters_update_poll();
+ vehicle_local_pos_poll(); // Check for new sensor values
vehicle_airspeed_poll();
+ vehicle_battery_poll();
+
if (_manual_control_sp.aux1 <= 0.0f) { /* vehicle is in mc mode */
_vtol_vehicle_status.vtol_in_rw_mode = true;
@@ -688,7 +771,8 @@ void VtolAttitudeControl::task_main()
if (fds[0].revents & POLLIN) {
vehicle_manual_poll(); /* update remote input */
orb_copy(ORB_ID(actuator_controls_virtual_mc), _actuator_inputs_mc, &_actuators_mc_in);
- // scale pitch control with airspeed
+
+ // scale pitch control with total airspeed
scale_mc_output();
fill_mc_att_control_output();
diff --git a/src/modules/vtol_att_control/vtol_att_control_params.c b/src/modules/vtol_att_control/vtol_att_control_params.c
index d1d4697f3..33752b2c4 100644
--- a/src/modules/vtol_att_control/vtol_att_control_params.c
+++ b/src/modules/vtol_att_control/vtol_att_control_params.c
@@ -64,7 +64,7 @@ PARAM_DEFINE_INT32(VT_IDLE_PWM_MC,900);
* @min 0.0
* @group VTOL Attitude Control
*/
-PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,2.0f);
+PARAM_DEFINE_FLOAT(VT_MC_ARSPD_MIN,10.0f);
/**
* Maximum airspeed in multicopter mode
@@ -109,3 +109,36 @@ PARAM_DEFINE_INT32(VT_FW_PERM_STAB,0);
*/
PARAM_DEFINE_FLOAT(VT_FW_PITCH_TRIM,0.0f);
+/**
+ * Motor max power
+ *
+ * Indicates the maximum power the motor is able to produce. Used to calculate
+ * propeller efficiency map.
+ *
+ * @min 1
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VT_POWER_MAX,120.0f);
+
+/**
+ * Propeller efficiency parameter
+ *
+ * Influences propeller efficiency at different power settings. Should be tuned beforehand.
+ *
+ * @min 0.5
+ * @max 0.9
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VT_PROP_EFF,0.0f);
+
+/**
+ * Total airspeed estimate low-pass filter gain
+ *
+ * Gain for tuning the low-pass filter for the total airspeed estimate
+ *
+ * @min 0.0
+ * @max 0.99
+ * @group VTOL Attitude Control
+ */
+PARAM_DEFINE_FLOAT(VT_ARSP_LP_GAIN,0.3f);
+
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
index 4a97d328c..077bc47c9 100644
--- a/src/systemcmds/config/config.c
+++ b/src/systemcmds/config/config.c
@@ -58,6 +58,7 @@
#include "systemlib/systemlib.h"
#include "systemlib/err.h"
+#include "systemlib/param/param.h"
__EXPORT int config_main(int argc, char *argv[]);
@@ -264,8 +265,11 @@ do_mag(int argc, char *argv[])
int srate = ioctl(fd, MAGIOCGSAMPLERATE, 0);
int prate = ioctl(fd, SENSORIOCGPOLLRATE, 0);
int range = ioctl(fd, MAGIOCGRANGE, 0);
+ int id = ioctl(fd, DEVIOCGDEVICEID,0);
+ int32_t calibration_id = 0;
+ param_get(param_find("SENS_MAG_ID"), &(calibration_id));
- warnx("mag: \n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d Ga", srate, prate, range);
+ warnx("mag: \n\tdevice id:\t%x\t(calibration is for device id %x)\n\tsample rate:\t%d Hz\n\tread rate:\t%d Hz\n\trange:\t%d Ga", id, calibration_id, srate, prate, range);
close(fd);
}
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 86e4ff545..bbd90b961 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -84,6 +84,7 @@ int preflight_check_main(int argc, char *argv[])
/* open text message output path */
int mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
int ret;
+ int32_t mag_devid,mag_calibration_devid;
/* give the system some time to sample the sensors in the background */
usleep(150000);
@@ -96,6 +97,16 @@ int preflight_check_main(int argc, char *argv[])
system_ok = false;
goto system_eval;
}
+
+ mag_devid = ioctl(fd, DEVIOCGDEVICEID,0);
+ param_get(param_find("SENS_MAG_ID"), &(mag_calibration_devid));
+ if (mag_devid != mag_calibration_devid){
+ warnx("magnetometer calibration is for a different device - calibrate magnetometer first");
+ mavlink_log_critical(mavlink_fd, "SENSOR FAIL: MAG CAL ID");
+ system_ok = false;
+ goto system_eval;
+ }
+
ret = ioctl(fd, MAGIOCSELFTEST, 0);
if (ret != OK) {