aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil2
-rw-r--r--ROMFS/px4fmu_common/init.d/rc.fw_apps9
-rw-r--r--ROMFS/px4fmu_common/init.d/rcS1
-rw-r--r--makefiles/config_px4fmu-v1_default.mk2
-rw-r--r--makefiles/config_px4fmu-v2_default.mk2
-rw-r--r--src/lib/geo/geo.c1
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp14
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp13
-rw-r--r--src/modules/fw_att_pos_estimator/estimator.cpp1887
-rw-r--r--src/modules/fw_att_pos_estimator/estimator.h173
-rw-r--r--src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp1112
-rw-r--r--src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c117
-rw-r--r--src/modules/fw_att_pos_estimator/module.mk42
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp11
-rw-r--r--src/modules/mavlink/orb_listener.c24
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c16
-rw-r--r--src/modules/sdlog2/sdlog2.c30
-rw-r--r--src/modules/sensors/sensors.cpp15
-rw-r--r--src/modules/uORB/topics/esc_status.h9
-rw-r--r--src/modules/uORB/topics/filtered_bottom_flow.h3
-rw-r--r--src/modules/uORB/topics/mission.h3
-rw-r--r--src/modules/uORB/topics/navigation_capabilities.h10
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h5
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h20
-rw-r--r--src/modules/uORB/topics/rc_channels.h55
-rw-r--r--src/modules/uORB/topics/sensor_combined.h17
-rw-r--r--src/modules/uORB/topics/subsystem_info.h3
-rw-r--r--src/modules/uORB/topics/telemetry_status.h24
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h3
-rw-r--r--src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h3
-rw-r--r--src/modules/uORB/topics/vehicle_command.h91
-rw-r--r--src/modules/uORB/topics/vehicle_control_debug.h9
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h16
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h12
-rw-r--r--src/modules/uORB/topics/vehicle_global_velocity_setpoint.h3
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h5
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h3
-rw-r--r--src/modules/uORB/topics/vehicle_local_position_setpoint.h3
-rw-r--r--src/modules/uORB/topics/vehicle_rates_setpoint.h9
-rw-r--r--src/modules/uORB/topics/vehicle_status.h49
-rw-r--r--src/modules/uORB/topics/vehicle_vicon_position.h3
41 files changed, 3569 insertions, 260 deletions
diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
index 36194ad68..d114fe21a 100644
--- a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
+++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
@@ -7,7 +7,7 @@
sh /etc/init.d/rc.fw_defaults
-echo "HIL Rascal 110 starting.."
+echo "X Plane HIL starting.."
set HIL yes
diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_apps b/ROMFS/px4fmu_common/init.d/rc.fw_apps
index 72327c554..429abc5ec 100644
--- a/ROMFS/px4fmu_common/init.d/rc.fw_apps
+++ b/ROMFS/px4fmu_common/init.d/rc.fw_apps
@@ -3,6 +3,13 @@
# Standard apps for fixed wing
#
-att_pos_estimator_ekf start
+#
+# Start the attitude and position estimator
+#
+fw_att_pos_estimator start
+
+#
+# Start attitude controller
+#
fw_att_control start
fw_pos_control_l1 start
diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS
index 57299d772..8ca14b320 100644
--- a/ROMFS/px4fmu_common/init.d/rcS
+++ b/ROMFS/px4fmu_common/init.d/rcS
@@ -390,6 +390,7 @@ then
then
sleep 1
mavlink start -b 230400 -d /dev/ttyACM0
+ gps start
usleep 5000
else
if [ $TTYS1_BUSY == yes ]
diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk
index aff614cbb..c47b773af 100644
--- a/makefiles/config_px4fmu-v1_default.mk
+++ b/makefiles/config_px4fmu-v1_default.mk
@@ -69,7 +69,7 @@ MODULES += modules/gpio_led
# Estimation modules (EKF/ SO3 / other filters)
#
MODULES += modules/attitude_estimator_ekf
-MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/fw_att_pos_estimator
MODULES += modules/position_estimator_inav
#MODULES += examples/flow_position_estimator
diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk
index 2ad2f63a9..b246befdb 100644
--- a/makefiles/config_px4fmu-v2_default.mk
+++ b/makefiles/config_px4fmu-v2_default.mk
@@ -77,7 +77,7 @@ MODULES += modules/mavlink_onboard
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/attitude_estimator_so3
-MODULES += modules/att_pos_estimator_ekf
+MODULES += modules/fw_att_pos_estimator
MODULES += modules/position_estimator_inav
MODULES += examples/flow_position_estimator
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
index 9b3e202e6..34285e2bf 100644
--- a/src/lib/geo/geo.c
+++ b/src/lib/geo/geo.c
@@ -197,7 +197,6 @@ __EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, doub
double lat_next_rad = lat_next * M_DEG_TO_RAD;
double lon_next_rad = lon_next * M_DEG_TO_RAD;
- double d_lat = lat_next_rad - lat_now_rad;
double d_lon = lon_next_rad - lon_now_rad;
/* conscious mix of double and float trig function to maximize speed and efficiency */
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 00bd23f83..10a6cd2c5 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -277,7 +277,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
// XXX write this out to perf regs
/* keep track of sensor updates */
- uint32_t sensor_last_count[3] = {0, 0, 0};
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
struct attitude_estimator_ekf_params ekf_params;
@@ -380,9 +379,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
uint8_t update_vect[3] = {0, 0, 0};
/* Fill in gyro measurements */
- if (sensor_last_count[0] != raw.gyro_counter) {
+ if (sensor_last_timestamp[0] != raw.timestamp) {
update_vect[0] = 1;
- sensor_last_count[0] = raw.gyro_counter;
sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -392,11 +390,10 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
z_k[2] = raw.gyro_rad_s[2] - gyro_offsets[2];
/* update accelerometer measurements */
- if (sensor_last_count[1] != raw.accelerometer_counter) {
+ if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
update_vect[1] = 1;
- sensor_last_count[1] = raw.accelerometer_counter;
sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
- sensor_last_timestamp[1] = raw.timestamp;
+ sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
hrt_abstime vel_t = 0;
@@ -445,11 +442,10 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
z_k[5] = raw.accelerometer_m_s2[2] - acc(2);
/* update magnetometer measurements */
- if (sensor_last_count[2] != raw.magnetometer_counter) {
+ if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
update_vect[2] = 1;
- sensor_last_count[2] = raw.magnetometer_counter;
sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
- sensor_last_timestamp[2] = raw.timestamp;
+ sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
z_k[6] = raw.magnetometer_ga[0];
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index e79726613..e2d69cd61 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -526,9 +526,8 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
uint8_t update_vect[3] = {0, 0, 0};
/* Fill in gyro measurements */
- if (sensor_last_count[0] != raw.gyro_counter) {
+ if (sensor_last_timestamp[0] != raw.timestamp) {
update_vect[0] = 1;
- sensor_last_count[0] = raw.gyro_counter;
sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -538,11 +537,10 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
gyro[2] = raw.gyro_rad_s[2] - gyro_offsets[2];
/* update accelerometer measurements */
- if (sensor_last_count[1] != raw.accelerometer_counter) {
+ if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
update_vect[1] = 1;
- sensor_last_count[1] = raw.accelerometer_counter;
sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
- sensor_last_timestamp[1] = raw.timestamp;
+ sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
acc[0] = raw.accelerometer_m_s2[0];
@@ -550,11 +548,10 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
acc[2] = raw.accelerometer_m_s2[2];
/* update magnetometer measurements */
- if (sensor_last_count[2] != raw.magnetometer_counter) {
+ if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
update_vect[2] = 1;
- sensor_last_count[2] = raw.magnetometer_counter;
sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
- sensor_last_timestamp[2] = raw.timestamp;
+ sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
mag[0] = raw.magnetometer_ga[0];
diff --git a/src/modules/fw_att_pos_estimator/estimator.cpp b/src/modules/fw_att_pos_estimator/estimator.cpp
new file mode 100644
index 000000000..cbbb5d7a0
--- /dev/null
+++ b/src/modules/fw_att_pos_estimator/estimator.cpp
@@ -0,0 +1,1887 @@
+#include "estimator.h"
+
+// 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
+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; // 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 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
+
+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 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 = 0; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
+float EAS2TAS = 1.0f; // ratio f true to equivalent airspeed
+
+// GPS input data variables
+float gpsCourse;
+float gpsVelD;
+float gpsLat;
+float gpsLon;
+float gpsHgt;
+uint8_t GPSstatus;
+
+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
+
+// Baro input
+float baroHgt;
+
+bool statesInitialised = false;
+
+bool fuseVelData = false; // this boolean causes the posNE and velNED obs to be fused
+bool fusePosData = false; // this boolean causes the posNE and velNED obs to be fused
+bool fuseHgtData = false; // this boolean causes the hgtMea obs to be fused
+bool fuseMagData = false; // boolean true when magnetometer data is to be fused
+bool fuseVtasData = false; // boolean true when airspeed data is to be fused
+
+bool onGround = true; // boolean true when the flight vehicle is on the ground (not flying)
+bool useAirspeed = true; // boolean true if airspeed data is being used
+bool useCompass = true; // boolean true if magnetometer data is being used
+
+float Vector3f::length(void) const
+{
+ return sqrt(x*x + y*y + z*z);
+}
+
+Vector3f Vector3f::zero(void) const
+{
+ Vector3f ret = *this;
+ ret.x = 0.0;
+ ret.y = 0.0;
+ ret.z = 0.0;
+ return ret;
+}
+
+Mat3f::Mat3f() {
+ x.x = 1.0f;
+ x.y = 0.0f;
+ x.z = 0.0f;
+
+ y.x = 0.0f;
+ y.y = 1.0f;
+ y.z = 0.0f;
+
+ z.x = 0.0f;
+ z.y = 0.0f;
+ z.z = 1.0f;
+}
+
+Mat3f Mat3f::transpose(void) const
+{
+ Mat3f ret = *this;
+ swap_var(ret.x.y, ret.y.x);
+ swap_var(ret.x.z, ret.z.x);
+ swap_var(ret.y.z, ret.z.y);
+ return ret;
+}
+
+// overload + operator to provide a vector addition
+Vector3f operator+( Vector3f vecIn1, Vector3f vecIn2)
+{
+ Vector3f vecOut;
+ vecOut.x = vecIn1.x + vecIn2.x;
+ vecOut.y = vecIn1.y + vecIn2.y;
+ vecOut.z = vecIn1.z + vecIn2.z;
+ return vecOut;
+}
+
+// overload - operator to provide a vector subtraction
+Vector3f operator-( Vector3f vecIn1, Vector3f vecIn2)
+{
+ Vector3f vecOut;
+ vecOut.x = vecIn1.x - vecIn2.x;
+ vecOut.y = vecIn1.y - vecIn2.y;
+ vecOut.z = vecIn1.z - vecIn2.z;
+ return vecOut;
+}
+
+// overload * operator to provide a matrix vector product
+Vector3f operator*( Mat3f matIn, Vector3f vecIn)
+{
+ Vector3f vecOut;
+ vecOut.x = matIn.x.x*vecIn.x + matIn.x.y*vecIn.y + matIn.x.z*vecIn.z;
+ vecOut.y = matIn.y.x*vecIn.x + matIn.y.y*vecIn.y + matIn.y.z*vecIn.z;
+ vecOut.z = matIn.x.x*vecIn.x + matIn.z.y*vecIn.y + matIn.z.z*vecIn.z;
+ return vecOut;
+}
+
+// overload % operator to provide a vector cross product
+Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2)
+{
+ Vector3f vecOut;
+ vecOut.x = vecIn1.y*vecIn2.z - vecIn1.z*vecIn2.y;
+ vecOut.y = vecIn1.z*vecIn2.x - vecIn1.x*vecIn2.z;
+ vecOut.z = vecIn1.x*vecIn2.y - vecIn1.y*vecIn2.x;
+ return vecOut;
+}
+
+// overload * operator to provide a vector scaler product
+Vector3f operator*(Vector3f vecIn1, float sclIn1)
+{
+ Vector3f vecOut;
+ vecOut.x = vecIn1.x * sclIn1;
+ vecOut.y = vecIn1.y * sclIn1;
+ vecOut.z = vecIn1.z * sclIn1;
+ return vecOut;
+}
+
+// overload * operator to provide a vector scaler product
+Vector3f operator*(float sclIn1, Vector3f vecIn1)
+{
+ Vector3f vecOut;
+ vecOut.x = vecIn1.x * sclIn1;
+ vecOut.y = vecIn1.y * sclIn1;
+ vecOut.z = vecIn1.z * sclIn1;
+ return vecOut;
+}
+
+void swap_var(float &d1, float &d2)
+{
+ float tmp = d1;
+ d1 = d2;
+ d2 = tmp;
+}
+
+void 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;
+ float 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);
+ float 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 = sqrt(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;
+
+}
+
+void CovariancePrediction(float dt)
+{
+ // scalars
+ float windVelSigma;
+ float dAngBiasSigma;
+ // float dVelBiasSigma;
+ float magEarthSigma;
+ float magBodySigma;
+ 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
+ const float yawVarScale = 1.0f;
+ 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 (uint8_t i=0; i<= 20; 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 (uint8_t j=0; j<=20; j++)
+ {
+ nextP[i][j] = P[i][j];
+ nextP[j][i] = P[j][i];
+ }
+ }
+ }
+
+ // Force symmetry on the covariance matrix to prevent ill-conditioning
+ // of the matrix which would cause the filter to blow-up
+ for (uint8_t i=0; i<=20; i++) P[i][i] = nextP[i][i];
+ for (uint8_t i=1; i<=20; i++)
+ {
+ for (uint8_t j=0; j<=i-1; j++)
+ {
+ P[i][j] = 0.5f*(nextP[i][j] + nextP[j][i]);
+ P[j][i] = P[i][j];
+ }
+ }
+
+ //
+}
+
+void 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;
+ static uint32_t velFailTime = 0;
+ static uint32_t posFailTime = 0;
+ static uint32_t hgtFailTime = 0;
+ bool velHealth;
+ bool posHealth;
+ bool hgtHealth;
+ bool velTimeout;
+ bool posTimeout;
+ bool hgtTimeout;
+
+// 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.2*accNavMag; // additional error in GPS velocities caused by manoeuvring
+ posErr = 0.2*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
+ velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0*(varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]);
+ velTimeout = (millis() - velFailTime) > horizRetryTime;
+ if (velHealth || velTimeout)
+ {
+ velHealth = true;
+ velFailTime = millis();
+ }
+ else
+ {
+ 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
+ posHealth = (sq(posInnov[0]) + sq(posInnov[1])) < 100.0f*(varInnovVelPos[3] + varInnovVelPos[4]);
+ posTimeout = (millis() - posFailTime) > horizRetryTime;
+ if (posHealth || posTimeout)
+ {
+ posHealth = true;
+ posFailTime = millis();
+ }
+ else
+ {
+ posHealth = false;
+ }
+ }
+ // test height measurements
+ if (fuseHgtData)
+ {
+ hgtInnov = statesAtHgtTime[9] + hgtMea;
+ varInnovVelPos[5] = P[9][9] + R_OBS[5];
+ // apply a 10-sigma threshold
+ hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5];
+ hgtTimeout = (millis() - hgtFailTime) > hgtRetryTime;
+ if (hgtHealth || hgtTimeout)
+ {
+ hgtHealth = true;
+ hgtFailTime = millis();
+ }
+ else
+ {
+ 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 && velHealth)
+ {
+ fuseData[0] = true;
+ fuseData[1] = true;
+ fuseData[2] = true;
+ }
+ if (fuseVelData && fusionModeGPS == 1 && velHealth)
+ {
+ fuseData[0] = true;
+ fuseData[1] = true;
+ }
+ if (fusePosData && fusionModeGPS <= 2 && posHealth)
+ {
+ fuseData[3] = true;
+ fuseData[4] = true;
+ }
+ if (fuseHgtData && 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];
+ }
+ }
+ }
+ }
+ }
+
+ //printf("velh: %s, posh: %s, hgth: %s\n", ((velHealth) ? "OK" : "FAIL"), ((posHealth) ? "OK" : "FAIL"), ((hgtHealth) ? "OK" : "FAIL"));
+}
+
+void 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;
+}
+
+void 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 = sqrt((ve - vwe)*(ve - vwe) + (vn - vwn)*(vn - vwn) + vd*vd);
+ // Perform fusion of True Airspeed measurement
+ if (useAirspeed && fuseVtasData && (VtasPred > 1.0) && (VtasMeas > 8.0))
+ {
+ // Calculate observation jacobians
+ SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
+ SH_TAS[1] = (SH_TAS[0]*(2*ve - 2*vwe))/2;
+ SH_TAS[2] = (SH_TAS[0]*(2*vn - 2*vwn))/2;
+
+ 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];
+ }
+ }
+ }
+ }
+}
+
+void 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 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 sq(float valIn)
+{
+ return valIn*valIn;
+}
+
+// Store states in a history array along with time stamp
+void StoreStates(uint64_t timestamp_ms)
+{
+ /* static to keep the store index */
+ static uint8_t storeIndex = 0;
+ 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;
+}
+
+// Output the state vector stored at the time that best matches that specified by msec
+void RecallStates(float (&statesForFusion)[n_states], uint64_t msec)
+{
+ int 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.
+ int 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++) statesForFusion[i] = storedStates[i][bestStoreIndex];
+ }
+ else // otherwise output current state
+ {
+ for (uint8_t i=0; i < n_states; i++) statesForFusion[i] = states[i];
+ }
+}
+
+void 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 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 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 quat2eul(float (&y)[3], const float (&u)[4])
+{
+ y[0] = atan2((2.0*(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] = -asin(2.0*(u[1]*u[3]-u[0]*u[2]));
+ y[2] = atan2((2.0*(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 calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD)
+{
+ velNED[0] = gpsGndSpd*cos(gpsCourse);
+ velNED[1] = gpsGndSpd*sin(gpsCourse);
+ velNED[2] = gpsVelD;
+}
+
+void 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 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 OnGroundCheck()
+{
+ onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
+}
+
+void 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 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];
+}
+
+
+
+void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, 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);
+
+ 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 InitialiseFilter(float (&initvelNED)[3])
+{
+ // 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;
+ }
+
+ // 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, 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;
+
+ //store initial lat,long and height
+ latRef = gpsLat;
+ lonRef = gpsLon;
+ hgtRef = gpsHgt;
+
+ // 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;
+}
diff --git a/src/modules/fw_att_pos_estimator/estimator.h b/src/modules/fw_att_pos_estimator/estimator.h
new file mode 100644
index 000000000..d68ac1d34
--- /dev/null
+++ b/src/modules/fw_att_pos_estimator/estimator.h
@@ -0,0 +1,173 @@
+#include <math.h>
+#include <stdint.h>
+
+#pragma once
+
+#define GRAVITY_MSS 9.80665f
+#define deg2rad 0.017453292f
+#define rad2deg 57.295780f
+#define pi 3.141592657f
+#define earthRate 0.000072921f
+#define earthRadius 6378145.0f
+#define earthRadiusInv 1.5678540e-7f
+
+class Vector3f
+{
+private:
+public:
+ float x;
+ float y;
+ float z;
+
+ float length(void) const;
+ Vector3f zero(void) const;
+};
+
+class Mat3f
+{
+private:
+public:
+ Vector3f x;
+ Vector3f y;
+ Vector3f z;
+
+ Mat3f();
+
+ Mat3f transpose(void) const;
+};
+
+Vector3f operator*(float sclIn1, Vector3f vecIn1);
+Vector3f operator+( Vector3f vecIn1, Vector3f vecIn2);
+Vector3f operator-( Vector3f vecIn1, Vector3f vecIn2);
+Vector3f operator*( Mat3f matIn, Vector3f vecIn);
+Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2);
+Vector3f operator*(Vector3f vecIn1, float sclIn1);
+
+void swap_var(float &d1, float &d2);
+
+const unsigned int n_states = 21;
+const unsigned int data_buffer_size = 50;
+
+extern uint32_t statetimeStamp[data_buffer_size]; // time stamp for each state vector stored
+extern Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
+extern Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
+extern Vector3f summedDelAng; // summed delta angles about the xyz body axes corrected for errors (rad)
+extern Vector3f summedDelVel; // summed delta velocities along the XYZ body axes corrected for errors (m/s)
+extern float accNavMag; // magnitude of navigation accel (- used to adjust GPS obs variance (m/s^2)
+extern Vector3f earthRateNED; // earths angular rate vector in NED (rad/s)
+extern Vector3f angRate; // angular rate vector in XYZ body axes measured by the IMU (rad/s)
+extern Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
+extern Vector3f dVelIMU;
+extern Vector3f dAngIMU;
+
+extern float P[n_states][n_states]; // covariance matrix
+extern float Kfusion[n_states]; // Kalman gains
+extern float states[n_states]; // state matrix
+extern float storedStates[n_states][data_buffer_size]; // state vectors stored for the last 50 time steps
+
+extern Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
+extern Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
+extern Vector3f summedDelAng; // summed delta angles about the xyz body axes corrected for errors (rad)
+extern Vector3f summedDelVel; // summed delta velocities along the XYZ body axes corrected for errors (m/s)
+
+extern float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec)
+
+extern bool onGround; // boolean true when the flight vehicle is on the ground (not flying)
+extern bool useAirspeed; // boolean true if airspeed data is being used
+extern bool useCompass; // boolean true if magnetometer data is being used
+extern uint8_t fusionModeGPS ; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
+extern float innovVelPos[6]; // innovation output
+extern float varInnovVelPos[6]; // innovation variance output
+
+extern bool fuseVelData; // this boolean causes the posNE and velNED obs to be fused
+extern bool fusePosData; // this boolean causes the posNE and velNED obs to be fused
+extern bool fuseHgtData; // this boolean causes the hgtMea obs to be fused
+extern bool fuseMagData; // boolean true when magnetometer data is to be fused
+
+extern float velNED[3]; // North, East, Down velocity obs (m/s)
+extern float posNE[2]; // North, East position obs (m)
+extern float hgtMea; // measured height (m)
+extern float posNED[3]; // North, East Down position (m)
+
+extern float statesAtVelTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
+extern float statesAtPosTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
+extern float statesAtHgtTime[n_states]; // States at the effective measurement time for the hgtMea measurement
+
+extern float innovMag[3]; // innovation output
+extern float varInnovMag[3]; // innovation variance output
+extern Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
+extern float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
+extern float innovVtas; // innovation output
+extern float varInnovVtas; // innovation variance output
+extern bool fuseVtasData; // boolean true when airspeed data is to be fused
+extern float VtasMeas; // true airspeed measurement (m/s)
+extern float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
+extern float latRef; // WGS-84 latitude of reference point (rad)
+extern float lonRef; // WGS-84 longitude of reference point (rad)
+extern float hgtRef; // WGS-84 height of reference point (m)
+extern Vector3f magBias; // states representing magnetometer bias vector in XYZ body axes
+extern uint8_t covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
+extern float EAS2TAS; // ratio f true to equivalent airspeed
+
+// GPS input data variables
+extern float gpsCourse;
+extern float gpsVelD;
+extern float gpsLat;
+extern float gpsLon;
+extern float gpsHgt;
+extern uint8_t GPSstatus;
+
+// Baro input
+extern float baroHgt;
+
+extern bool statesInitialised;
+
+const float covTimeStepMax = 0.07f; // maximum time allowed between covariance predictions
+const float covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
+
+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);
+
+float sq(float valIn);
+
+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 stste vector stored at closest time to the one specified by msec
+void RecallStates(float (&statesForFusion)[n_states], uint64_t msec);
+
+void quat2Tbn(Mat3f &Tbn, const float (&quat)[4]);
+
+void calcEarthRateNED(Vector3f &omega, float latitude);
+
+void eul2quat(float (&quat)[4], const float (&eul)[3]);
+
+void quat2eul(float (&eul)[3], const float (&quat)[4]);
+
+void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
+
+void calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+
+void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+
+void OnGroundCheck();
+
+void CovarianceInit();
+
+void InitialiseFilter(float (&initvelNED)[3]);
+
+uint32_t millis();
+
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
new file mode 100644
index 000000000..082c695dc
--- /dev/null
+++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
@@ -0,0 +1,1112 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file fw_att_pos_estimator_main.cpp
+ * Implementation of the attitude and position estimator.
+ *
+ * @author Paul Riseborough <p_riseborough@live.com.au>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <math.h>
+#include <poll.h>
+#include <time.h>
+#include <drivers/drv_hrt.h>
+
+#define SENSOR_COMBINED_SUB
+
+
+#include <drivers/drv_gyro.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_mag.h>
+#include <drivers/drv_baro.h>
+#ifdef SENSOR_COMBINED_SUB
+#include <uORB/topics/sensor_combined.h>
+#endif
+#include <arch/board/board.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/airspeed.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/parameter_update.h>
+#include <systemlib/param/param.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
+#include <mathlib/mathlib.h>
+#include <mavlink/mavlink_log.h>
+
+#include "estimator.h"
+
+
+
+/**
+ * estimator app start / stop handling function
+ *
+ * @ingroup apps
+ */
+extern "C" __EXPORT int fw_att_pos_estimator_main(int argc, char *argv[]);
+
+__EXPORT uint32_t millis();
+
+static uint64_t last_run = 0;
+static uint64_t IMUmsec = 0;
+
+uint32_t millis()
+{
+ return IMUmsec;
+}
+
+static void print_status();
+
+class FixedwingEstimator
+{
+public:
+ /**
+ * Constructor
+ */
+ FixedwingEstimator();
+
+ /**
+ * Destructor, also kills the sensors task.
+ */
+ ~FixedwingEstimator();
+
+ /**
+ * Start the sensors task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _estimator_task; /**< task handle for sensor task */
+#ifndef SENSOR_COMBINED_SUB
+ int _gyro_sub; /**< gyro sensor subscription */
+ int _accel_sub; /**< accel sensor subscription */
+ int _mag_sub; /**< mag sensor subscription */
+#else
+ int _sensor_combined_sub;
+#endif
+ int _airspeed_sub; /**< airspeed subscription */
+ int _baro_sub; /**< barometer subscription */
+ int _gps_sub; /**< GPS subscription */
+ int _vstatus_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_control_sub; /**< notification of manual control updates */
+ int _mission_sub;
+
+ orb_advert_t _att_pub; /**< vehicle attitude */
+ orb_advert_t _global_pos_pub; /**< global position */
+ orb_advert_t _local_pos_pub; /**< position in local frame */
+
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct gyro_report _gyro;
+ struct accel_report _accel;
+ struct mag_report _mag;
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct baro_report _baro; /**< baro readings */
+ struct vehicle_status_s _vstatus; /**< vehicle status */
+ struct vehicle_global_position_s _global_pos; /**< global vehicle position */
+ struct vehicle_local_position_s _local_pos; /**< local vehicle position */
+ struct vehicle_gps_position_s _gps; /**< GPS position */
+
+ struct gyro_scale _gyro_offsets;
+ struct accel_scale _accel_offsets;
+ struct mag_scale _mag_offsets;
+
+#ifdef SENSOR_COMBINED_SUB
+ struct sensor_combined_s _sensor_combined;
+#endif
+
+ float _baro_ref; /**< barometer reference altitude */
+ float _baro_gps_offset; /**< offset between GPS and baro */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _perf_gyro; ///<local performance counter for gyro updates
+ perf_counter_t _perf_accel; ///<local performance counter for accel updates
+ perf_counter_t _perf_mag; ///<local performance counter for mag updates
+ perf_counter_t _perf_gps; ///<local performance counter for gps updates
+ perf_counter_t _perf_baro; ///<local performance counter for baro updates
+ perf_counter_t _perf_airspeed; ///<local performance counter for airspeed updates
+
+ bool _initialized;
+ bool _gps_initialized;
+
+ int _mavlink_fd;
+
+ struct {
+ int32_t vel_delay_ms;
+ int32_t pos_delay_ms;
+ int32_t height_delay_ms;
+ int32_t mag_delay_ms;
+ int32_t tas_delay_ms;
+ } _parameters; /**< local copies of interesting parameters */
+
+ struct {
+ param_t vel_delay_ms;
+ param_t pos_delay_ms;
+ param_t height_delay_ms;
+ param_t mag_delay_ms;
+ param_t tas_delay_ms;
+ } _parameter_handles; /**< handles for interesting parameters */
+
+
+ /**
+ * Update our local parameter cache.
+ */
+ int parameters_update();
+
+ /**
+ * Update control outputs
+ *
+ */
+ void control_update();
+
+ /**
+ * Check for changes in vehicle status.
+ */
+ void vehicle_status_poll();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main sensor collection task.
+ */
+ void task_main() __attribute__((noreturn));
+};
+
+namespace estimator
+{
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+FixedwingEstimator *g_estimator;
+}
+
+FixedwingEstimator::FixedwingEstimator() :
+
+ _task_should_exit(false),
+ _estimator_task(-1),
+
+/* subscriptions */
+#ifndef SENSOR_COMBINED_SUB
+ _gyro_sub(-1),
+ _accel_sub(-1),
+ _mag_sub(-1),
+#else
+ _sensor_combined_sub(-1),
+#endif
+ _airspeed_sub(-1),
+ _baro_sub(-1),
+ _gps_sub(-1),
+ _vstatus_sub(-1),
+ _params_sub(-1),
+ _manual_control_sub(-1),
+
+/* publications */
+ _att_pub(-1),
+ _global_pos_pub(-1),
+ _local_pos_pub(-1),
+
+ _baro_ref(0.0f),
+ _baro_gps_offset(0.0f),
+
+/* performance counters */
+ _loop_perf(perf_alloc(PC_COUNT, "fw_att_pos_estimator")),
+ _perf_gyro(perf_alloc(PC_COUNT, "fw_ekf_gyro_upd")),
+ _perf_accel(perf_alloc(PC_COUNT, "fw_ekf_accel_upd")),
+ _perf_mag(perf_alloc(PC_COUNT, "fw_ekf_mag_upd")),
+ _perf_gps(perf_alloc(PC_COUNT, "fw_ekf_gps_upd")),
+ _perf_baro(perf_alloc(PC_COUNT, "fw_ekf_baro_upd")),
+ _perf_airspeed(perf_alloc(PC_COUNT, "fw_ekf_aspd_upd")),
+
+/* states */
+ _initialized(false),
+ _gps_initialized(false),
+ _mavlink_fd(-1)
+{
+
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+
+ _parameter_handles.vel_delay_ms = param_find("PE_VEL_DELAY_MS");
+ _parameter_handles.pos_delay_ms = param_find("PE_POS_DELAY_MS");
+ _parameter_handles.height_delay_ms = param_find("PE_HGT_DELAY_MS");
+ _parameter_handles.mag_delay_ms = param_find("PE_MAG_DELAY_MS");
+ _parameter_handles.tas_delay_ms = param_find("PE_TAS_DELAY_MS");
+
+ /* fetch initial parameter values */
+ parameters_update();
+
+ /* get offsets */
+
+ int fd, res;
+
+ fd = open(GYRO_DEVICE_PATH, O_RDONLY);
+
+ if (fd > 0) {
+ res = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&_gyro_offsets);
+ close(fd);
+ }
+
+ fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+
+ if (fd > 0) {
+ res = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&_accel_offsets);
+ close(fd);
+ }
+
+ fd = open(MAG_DEVICE_PATH, O_RDONLY);
+
+ if (fd > 0) {
+ res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&_mag_offsets);
+ close(fd);
+ }
+}
+
+FixedwingEstimator::~FixedwingEstimator()
+{
+ if (_estimator_task != -1) {
+
+ /* task wakes up every 100ms or so at the longest */
+ _task_should_exit = true;
+
+ /* wait for a second for the task to quit at our request */
+ unsigned i = 0;
+
+ do {
+ /* wait 20ms */
+ usleep(20000);
+
+ /* if we have given up, kill it */
+ if (++i > 50) {
+ task_delete(_estimator_task);
+ break;
+ }
+ } while (_estimator_task != -1);
+ }
+
+ estimator::g_estimator = nullptr;
+}
+
+int
+FixedwingEstimator::parameters_update()
+{
+
+ param_get(_parameter_handles.vel_delay_ms, &(_parameters.vel_delay_ms));
+ param_get(_parameter_handles.pos_delay_ms, &(_parameters.pos_delay_ms));
+ param_get(_parameter_handles.height_delay_ms, &(_parameters.height_delay_ms));
+ param_get(_parameter_handles.mag_delay_ms, &(_parameters.mag_delay_ms));
+ param_get(_parameter_handles.tas_delay_ms, &(_parameters.tas_delay_ms));
+
+ return OK;
+}
+
+void
+FixedwingEstimator::vehicle_status_poll()
+{
+ bool vstatus_updated;
+
+ /* Check HIL state if vehicle status has changed */
+ orb_check(_vstatus_sub, &vstatus_updated);
+
+ if (vstatus_updated) {
+
+ orb_copy(ORB_ID(vehicle_status), _vstatus_sub, &_vstatus);
+ }
+}
+
+void
+FixedwingEstimator::task_main_trampoline(int argc, char *argv[])
+{
+ estimator::g_estimator->task_main();
+}
+
+float dt = 0.0f; // time lapsed since last covariance prediction
+
+void
+FixedwingEstimator::task_main()
+{
+
+ /*
+ * do subscriptions
+ */
+ _baro_sub = orb_subscribe(ORB_ID(sensor_baro));
+ _airspeed_sub = orb_subscribe(ORB_ID(airspeed));
+ _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
+ _params_sub = orb_subscribe(ORB_ID(parameter_update));
+
+ /* rate limit vehicle status updates to 5Hz */
+ orb_set_interval(_vstatus_sub, 200);
+
+#ifndef SENSOR_COMBINED_SUB
+
+ _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro));
+ _accel_sub = orb_subscribe(ORB_ID(sensor_accel));
+ _mag_sub = orb_subscribe(ORB_ID(sensor_mag));
+
+ /* rate limit gyro updates to 50 Hz */
+ /* XXX remove this!, BUT increase the data buffer size! */
+ orb_set_interval(_gyro_sub, 4);
+#else
+ _sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+ /* XXX remove this!, BUT increase the data buffer size! */
+ orb_set_interval(_sensor_combined_sub, 4);
+#endif
+
+ parameters_update();
+
+ /* set initial filter state */
+ fuseVelData = false;
+ fusePosData = false;
+ fuseHgtData = false;
+ fuseMagData = false;
+ fuseVtasData = false;
+ statesInitialised = false;
+
+ /* initialize measurement data */
+ VtasMeas = 0.0f;
+ Vector3f lastAngRate = {0.0f, 0.0f, 0.0f};
+ Vector3f lastAccel = {0.0f, 0.0f, -9.81f};
+ dVelIMU.x = 0.0f;
+ dVelIMU.y = 0.0f;
+ dVelIMU.z = 0.0f;
+ dAngIMU.x = 0.0f;
+ dAngIMU.y = 0.0f;
+ dAngIMU.z = 0.0f;
+
+ /* wakeup source(s) */
+ struct pollfd fds[2];
+
+ /* Setup of loop */
+ fds[0].fd = _params_sub;
+ fds[0].events = POLLIN;
+#ifndef SENSOR_COMBINED_SUB
+ fds[1].fd = _gyro_sub;
+ fds[1].events = POLLIN;
+#else
+ fds[1].fd = _sensor_combined_sub;
+ fds[1].events = POLLIN;
+#endif
+
+ hrt_abstime start_time = hrt_absolute_time();
+
+ bool newDataGps = false;
+ bool newAdsData = false;
+ bool newDataMag = false;
+
+ while (!_task_should_exit) {
+
+ /* wait for up to 500ms for data */
+ int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
+
+ /* timed out - periodic check for _task_should_exit, etc. */
+ if (pret == 0)
+ continue;
+
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
+ if (pret < 0) {
+ warn("poll error %d, %d", pret, errno);
+ continue;
+ }
+
+ perf_begin(_loop_perf);
+
+ /* only update parameters if they changed */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), _params_sub, &update);
+
+ /* update parameters from storage */
+ parameters_update();
+ }
+
+ /* only run estimator if gyro updated */
+ if (fds[1].revents & POLLIN) {
+
+ /* check vehicle status for changes to publication state */
+ vehicle_status_poll();
+
+ bool accel_updated;
+ bool mag_updated;
+
+ perf_count(_perf_gyro);
+
+ /**
+ * PART ONE: COLLECT ALL DATA
+ **/
+
+ hrt_abstime last_sensor_timestamp;
+
+ /* load local copies */
+#ifndef SENSOR_COMBINED_SUB
+ orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro);
+
+
+ orb_check(_accel_sub, &accel_updated);
+
+ if (accel_updated) {
+ perf_count(_perf_accel);
+ orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ }
+
+ last_sensor_timestamp = _gyro.timestamp;
+ IMUmsec = _gyro.timestamp / 1e3f;
+
+ float deltaT = (_gyro.timestamp - last_run) / 1e6f;
+ last_run = _gyro.timestamp;
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f)
+ deltaT = 0.01f;
+
+
+ // Always store data, independent of init status
+ /* fill in last data set */
+ dtIMU = deltaT;
+
+ angRate.x = _gyro.x;
+ angRate.y = _gyro.y;
+ angRate.z = _gyro.z;
+
+ accel.x = _accel.x;
+ accel.y = _accel.y;
+ accel.z = _accel.z;
+
+ dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU;
+ lastAngRate = angRate;
+ dVelIMU = 0.5f * (accel + lastAccel) * dtIMU;
+ lastAccel = accel;
+
+
+#else
+ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
+
+ static hrt_abstime last_accel = 0;
+ static hrt_abstime last_mag = 0;
+
+ if (last_accel != _sensor_combined.accelerometer_timestamp) {
+ accel_updated = true;
+ }
+
+ last_accel = _sensor_combined.accelerometer_timestamp;
+
+
+ // Copy gyro and accel
+ last_sensor_timestamp = _sensor_combined.timestamp;
+ IMUmsec = _sensor_combined.timestamp / 1e3f;
+
+ float deltaT = (_sensor_combined.timestamp - last_run) / 1e6f;
+ last_run = _sensor_combined.timestamp;
+
+ /* guard against too large deltaT's */
+ if (deltaT > 1.0f || deltaT < 0.000001f)
+ deltaT = 0.01f;
+
+ // Always store data, independent of init status
+ /* fill in last data set */
+ dtIMU = deltaT;
+
+ angRate.x = _sensor_combined.gyro_rad_s[0];
+ angRate.y = _sensor_combined.gyro_rad_s[1];
+ angRate.z = _sensor_combined.gyro_rad_s[2];
+
+ accel.x = _sensor_combined.accelerometer_m_s2[0];
+ accel.y = _sensor_combined.accelerometer_m_s2[1];
+ accel.z = _sensor_combined.accelerometer_m_s2[2];
+
+ dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU;
+ lastAngRate = angRate;
+ dVelIMU = 0.5f * (accel + lastAccel) * dtIMU;
+ lastAccel = accel;
+
+ if (last_mag != _sensor_combined.magnetometer_timestamp) {
+ mag_updated = true;
+ newDataMag = true;
+
+ } else {
+ newDataMag = false;
+ }
+
+ last_mag = _sensor_combined.magnetometer_timestamp;
+
+#endif
+
+ bool airspeed_updated;
+ orb_check(_airspeed_sub, &airspeed_updated);
+
+ if (airspeed_updated) {
+ orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+ perf_count(_perf_airspeed);
+
+ VtasMeas = _airspeed.true_airspeed_m_s;
+ newAdsData = true;
+
+ } else {
+ newAdsData = false;
+ }
+
+ bool gps_updated;
+ orb_check(_gps_sub, &gps_updated);
+
+ if (gps_updated) {
+ orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps);
+ perf_count(_perf_gps);
+
+ if (_gps.fix_type < 3) {
+ gps_updated = false;
+ newDataGps = false;
+
+ } else {
+ /* fuse GPS updates */
+
+ //_gps.timestamp / 1e3;
+ GPSstatus = _gps.fix_type;
+ velNED[0] = _gps.vel_n_m_s;
+ velNED[1] = _gps.vel_e_m_s;
+ velNED[2] = _gps.vel_d_m_s;
+
+ // warnx("GPS updated: status: %d, vel: %8.4f %8.4f %8.4f", (int)GPSstatus, velNED[0], velNED[1], velNED[2]);
+
+ gpsLat = math::radians(_gps.lat / (double)1e7);
+ gpsLon = math::radians(_gps.lon / (double)1e7) - M_PI;
+ gpsHgt = _gps.alt / 1e3f;
+ newDataGps = true;
+
+ }
+
+ }
+
+ bool baro_updated;
+ orb_check(_baro_sub, &baro_updated);
+
+ if (baro_updated) {
+ orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
+
+ baroHgt = _baro.altitude - _baro_ref;
+
+ // Could use a blend of GPS and baro alt data if desired
+ hgtMea = 1.0f * baroHgt + 0.0f * gpsHgt;
+ }
+
+#ifndef SENSOR_COMBINED_SUB
+ orb_check(_mag_sub, &mag_updated);
+#endif
+
+ if (mag_updated) {
+
+ perf_count(_perf_mag);
+
+#ifndef SENSOR_COMBINED_SUB
+ orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag);
+
+ // XXX we compensate the offsets upfront - should be close to zero.
+ // 0.001f
+ magData.x = _mag.x;
+ magBias.x = 0.000001f; // _mag_offsets.x_offset
+
+ magData.y = _mag.y;
+ magBias.y = 0.000001f; // _mag_offsets.y_offset
+
+ magData.z = _mag.z;
+ magBias.z = 0.000001f; // _mag_offsets.y_offset
+
+#else
+
+ // XXX we compensate the offsets upfront - should be close to zero.
+ // 0.001f
+ magData.x = _sensor_combined.magnetometer_ga[0];
+ magBias.x = 0.000001f; // _mag_offsets.x_offset
+
+ magData.y = _sensor_combined.magnetometer_ga[1];
+ magBias.y = 0.000001f; // _mag_offsets.y_offset
+
+ magData.z = _sensor_combined.magnetometer_ga[2];
+ magBias.z = 0.000001f; // _mag_offsets.y_offset
+
+#endif
+
+ newDataMag = true;
+
+ } else {
+ newDataMag = false;
+ }
+
+
+ /**
+ * PART TWO: EXECUTE THE FILTER
+ **/
+
+ // Wait long enough to ensure all sensors updated once
+ // XXX we rather want to check all updated
+
+
+ if (hrt_elapsed_time(&start_time) > 100000) {
+
+ if (!_gps_initialized && (GPSstatus == 3)) {
+ velNED[0] = _gps.vel_n_m_s;
+ velNED[1] = _gps.vel_e_m_s;
+ velNED[2] = _gps.vel_d_m_s;
+
+ double lat = _gps.lat * 1e-7;
+ double lon = _gps.lon * 1e-7;
+ float alt = _gps.alt * 1e-3;
+
+ InitialiseFilter(velNED);
+
+ // Initialize projection
+ _local_pos.ref_lat = _gps.lat;
+ _local_pos.ref_lon = _gps.lon;
+ _local_pos.ref_alt = alt;
+ _local_pos.ref_timestamp = _gps.timestamp_position;
+
+ // Store
+ _baro_ref = baroHgt;
+ _baro_gps_offset = baroHgt - alt;
+
+ // XXX this is not multithreading safe
+ map_projection_init(lat, lon);
+ mavlink_log_info(_mavlink_fd, "[position estimator] init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
+
+ _gps_initialized = true;
+
+ } else if (!statesInitialised) {
+ velNED[0] = 0.0f;
+ velNED[1] = 0.0f;
+ velNED[2] = 0.0f;
+ posNED[0] = 0.0f;
+ posNED[1] = 0.0f;
+ posNED[2] = 0.0f;
+
+ posNE[0] = posNED[0];
+ posNE[1] = posNED[1];
+ InitialiseFilter(velNED);
+ }
+ }
+
+ // If valid IMU data and states initialised, predict states and covariances
+ if (statesInitialised) {
+ // Run the strapdown INS equations every IMU update
+ UpdateStrapdownEquationsNED();
+#if 0
+ // debug code - could be tunred into a filter mnitoring/watchdog function
+ float tempQuat[4];
+
+ for (uint8_t j = 0; j <= 3; j++) tempQuat[j] = states[j];
+
+ quat2eul(eulerEst, tempQuat);
+
+ for (uint8_t j = 0; j <= 2; j++) eulerDif[j] = eulerEst[j] - ahrsEul[j];
+
+ if (eulerDif[2] > pi) eulerDif[2] -= 2 * pi;
+
+ if (eulerDif[2] < -pi) eulerDif[2] += 2 * pi;
+
+#endif
+ // store the predicted states for subsequent use by measurement fusion
+ StoreStates(IMUmsec);
+ // Check if on ground - status is used by covariance prediction
+ OnGroundCheck();
+ // sum delta angles and time used by covariance prediction
+ summedDelAng = summedDelAng + correctedDelAng;
+ summedDelVel = summedDelVel + dVelIMU;
+ dt += dtIMU;
+
+ // perform a covariance prediction if the total delta angle has exceeded the limit
+ // or the time limit will be exceeded at the next IMU update
+ if ((dt >= (covTimeStepMax - dtIMU)) || (summedDelAng.length() > covDelAngMax)) {
+ CovariancePrediction(dt);
+ summedDelAng = summedDelAng.zero();
+ summedDelVel = summedDelVel.zero();
+ dt = 0.0f;
+ }
+
+ _initialized = true;
+ }
+
+ // Fuse GPS Measurements
+ if (newDataGps && _gps_initialized) {
+ // Convert GPS measurements to Pos NE, hgt and Vel NED
+ velNED[0] = _gps.vel_n_m_s;
+ velNED[1] = _gps.vel_e_m_s;
+ velNED[2] = _gps.vel_d_m_s;
+ calcposNED(posNED, gpsLat, gpsLon, gpsHgt, latRef, lonRef, hgtRef);
+
+ posNE[0] = posNED[0];
+ posNE[1] = posNED[1];
+ // set fusion flags
+ fuseVelData = true;
+ fusePosData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ RecallStates(statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
+ RecallStates(statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
+ // run the fusion step
+ FuseVelposNED();
+
+ } else if (statesInitialised) {
+ // Convert GPS measurements to Pos NE, hgt and Vel NED
+ velNED[0] = 0.0f;
+ velNED[1] = 0.0f;
+ velNED[2] = 0.0f;
+ posNED[0] = 0.0f;
+ posNED[1] = 0.0f;
+ posNED[2] = 0.0f;
+
+ posNE[0] = posNED[0];
+ posNE[1] = posNED[1];
+ // set fusion flags
+ fuseVelData = true;
+ fusePosData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ RecallStates(statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
+ RecallStates(statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
+ // run the fusion step
+ FuseVelposNED();
+
+ } else {
+ fuseVelData = false;
+ fusePosData = false;
+ }
+
+ if (newAdsData && statesInitialised) {
+ // Could use a blend of GPS and baro alt data if desired
+ hgtMea = 1.0f * baroHgt + 0.0f * gpsHgt;
+ fuseHgtData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ RecallStates(statesAtHgtTime, (IMUmsec - _parameters.height_delay_ms));
+ // run the fusion step
+ FuseVelposNED();
+
+ } else {
+ fuseHgtData = false;
+ }
+
+ // Fuse Magnetometer Measurements
+ if (newDataMag && statesInitialised) {
+ fuseMagData = true;
+ RecallStates(statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data
+
+ } else {
+ fuseMagData = false;
+ }
+
+ if (statesInitialised) FuseMagnetometer();
+
+ // Fuse Airspeed Measurements
+ if (newAdsData && statesInitialised && VtasMeas > 8.0f) {
+ fuseVtasData = true;
+ RecallStates(statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data
+ FuseAirspeed();
+
+ } else {
+ fuseVtasData = false;
+ }
+
+ // Publish results
+ if (_initialized) {
+
+
+
+ // 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 - milligauss (North, East, Down)
+ // 18-20: Body Magnetic Field Vector - milligauss (X,Y,Z)
+
+ math::Quaternion q(states[0], states[1], states[2], states[3]);
+ math::Matrix<3, 3> R = q.to_dcm();
+ math::Vector<3> euler = R.to_euler();
+
+ for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
+ _att.R[i][j] = R(i, j);
+
+ _att.timestamp = last_sensor_timestamp;
+ _att.q[0] = states[0];
+ _att.q[1] = states[1];
+ _att.q[2] = states[2];
+ _att.q[3] = states[3];
+ _att.q_valid = true;
+ _att.R_valid = true;
+
+ _att.timestamp = last_sensor_timestamp;
+ _att.roll = euler(0);
+ _att.pitch = euler(1);
+ _att.yaw = euler(2);
+
+ _att.rollspeed = angRate.x - states[10];
+ _att.pitchspeed = angRate.y - states[11];
+ _att.yawspeed = angRate.z - states[12];
+ // gyro offsets
+ _att.rate_offsets[0] = states[10];
+ _att.rate_offsets[1] = states[11];
+ _att.rate_offsets[2] = states[12];
+
+ /* lazily publish the attitude only once available */
+ if (_att_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_attitude), _att_pub, &_att);
+
+ } else {
+ /* advertise and publish */
+ _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &_att);
+ }
+ }
+
+ if (!isfinite(states[0])) {
+ print_status();
+ _exit(0);
+ }
+
+ if (_gps_initialized) {
+ _local_pos.timestamp = last_sensor_timestamp;
+ _local_pos.x = states[7];
+ _local_pos.y = states[8];
+ _local_pos.z = states[9];
+
+ _local_pos.vx = states[4];
+ _local_pos.vy = states[5];
+ _local_pos.vz = states[6];
+
+ _local_pos.xy_valid = _gps_initialized;
+ _local_pos.z_valid = true;
+ _local_pos.v_xy_valid = _gps_initialized;
+ _local_pos.v_z_valid = true;
+ _local_pos.xy_global = true;
+
+ _local_pos.z_global = false;
+
+ /* lazily publish the local position only once available */
+ if (_local_pos_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_local_position), _local_pos_pub, &_local_pos);
+
+ } else {
+ /* advertise and publish */
+ _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &_local_pos);
+ }
+
+ _global_pos.timestamp = _local_pos.timestamp;
+
+ _global_pos.baro_valid = true;
+ _global_pos.global_valid = true;
+
+ if (_local_pos.xy_global) {
+ double est_lat, est_lon;
+ map_projection_reproject(_local_pos.x, _local_pos.y, &est_lat, &est_lon);
+ _global_pos.lat = est_lat;
+ _global_pos.lon = est_lon;
+ _global_pos.time_gps_usec = _gps.time_gps_usec;
+ }
+
+ /* set valid values even if position is not valid */
+ if (_local_pos.v_xy_valid) {
+ _global_pos.vel_n = _local_pos.vx;
+ _global_pos.vel_e = _local_pos.vy;
+ } else {
+ _global_pos.vel_n = 0.0f;
+ _global_pos.vel_e = 0.0f;
+ }
+
+ _global_pos.alt = _local_pos.ref_alt - _local_pos.z;
+
+ if (_local_pos.z_valid) {
+ _global_pos.baro_alt = _baro_ref - _baro_gps_offset - _local_pos.z;
+ }
+
+ if (_local_pos.v_z_valid) {
+ _global_pos.vel_d = _local_pos.vz;
+ }
+
+ _global_pos.yaw = _local_pos.yaw;
+
+ _global_pos.timestamp = _local_pos.timestamp;
+
+ /* lazily publish the global position only once available */
+ if (_global_pos_pub > 0) {
+ /* publish the attitude setpoint */
+ orb_publish(ORB_ID(vehicle_global_position), _global_pos_pub, &_global_pos);
+
+ } else {
+ /* advertise and publish */
+ _global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos);
+ }
+ }
+
+ }
+
+ perf_end(_loop_perf);
+ }
+
+ warnx("exiting.\n");
+
+ _estimator_task = -1;
+ _exit(0);
+}
+
+int
+FixedwingEstimator::start()
+{
+ ASSERT(_estimator_task == -1);
+
+ /* start the task */
+ _estimator_task = task_spawn_cmd("fw_att_pos_estimator",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 40,
+ 6000,
+ (main_t)&FixedwingEstimator::task_main_trampoline,
+ nullptr);
+
+ if (_estimator_task < 0) {
+ warn("task start failed");
+ return -errno;
+ }
+
+ return OK;
+}
+
+void print_status()
+{
+ math::Quaternion q(states[0], states[1], states[2], states[3]);
+ math::Matrix<3, 3> R = q.to_dcm();
+ math::Vector<3> euler = R.to_euler();
+
+ printf("attitude: roll: %8.4f, pitch %8.4f, yaw: %8.4f degrees\n",
+ (double)math::degrees(euler(0)), (double)math::degrees(euler(1)), (double)math::degrees(euler(2)));
+
+ // 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 - milligauss (North, East, Down)
+ // 18-20: Body Magnetic Field Vector - milligauss (X,Y,Z)
+
+ printf("dtIMU: %8.6f dt: %8.6f IMUmsec: %d\n", dtIMU, dt, (int)IMUmsec);
+ printf("dvel: %8.6f %8.6f %8.6f accel: %8.6f %8.6f %8.6f\n", (double)dVelIMU.x, (double)dVelIMU.y, (double)dVelIMU.z, (double)accel.x, (double)accel.y, (double)accel.z);
+ printf("dang: %8.4f %8.4f %8.4f dang corr: %8.4f %8.4f %8.4f\n" , (double)dAngIMU.x, (double)dAngIMU.y, (double)dAngIMU.z, (double)correctedDelAng.x, (double)correctedDelAng.y, (double)correctedDelAng.z);
+ printf("states (quat) [1-4]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)states[0], (double)states[1], (double)states[2], (double)states[3]);
+ printf("states (vel m/s) [5-7]: %8.4f, %8.4f, %8.4f\n", (double)states[4], (double)states[5], (double)states[6]);
+ printf("states (pos m) [8-10]: %8.4f, %8.4f, %8.4f\n", (double)states[7], (double)states[8], (double)states[9]);
+ printf("states (delta ang) [11-13]: %8.4f, %8.4f, %8.4f\n", (double)states[10], (double)states[11], (double)states[12]);
+ printf("states (wind) [14-15]: %8.4f, %8.4f\n", (double)states[13], (double)states[14]);
+ printf("states (earth mag) [16-18]: %8.4f, %8.4f, %8.4f\n", (double)states[15], (double)states[16], (double)states[17]);
+ printf("states (body mag) [19-21]: %8.4f, %8.4f, %8.4f\n", (double)states[18], (double)states[19], (double)states[20]);
+ printf("states: %s %s %s %s %s %s %s %s %s\n",
+ (statesInitialised) ? "INITIALIZED" : "NON_INIT",
+ (onGround) ? "ON_GROUND" : "AIRBORNE",
+ (fuseVelData) ? "FUSE_VEL" : "INH_VEL",
+ (fusePosData) ? "FUSE_POS" : "INH_POS",
+ (fuseHgtData) ? "FUSE_HGT" : "INH_HGT",
+ (fuseMagData) ? "FUSE_MAG" : "INH_MAG",
+ (fuseVtasData) ? "FUSE_VTAS" : "INH_VTAS",
+ (useAirspeed) ? "USE_AIRSPD" : "IGN_AIRSPD",
+ (useCompass) ? "USE_COMPASS" : "IGN_COMPASS");
+}
+
+int fw_att_pos_estimator_main(int argc, char *argv[])
+{
+ if (argc < 1)
+ errx(1, "usage: fw_att_pos_estimator {start|stop|status}");
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (estimator::g_estimator != nullptr)
+ errx(1, "already running");
+
+ estimator::g_estimator = new FixedwingEstimator;
+
+ if (estimator::g_estimator == nullptr)
+ errx(1, "alloc failed");
+
+ if (OK != estimator::g_estimator->start()) {
+ delete estimator::g_estimator;
+ estimator::g_estimator = nullptr;
+ err(1, "start failed");
+ }
+
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ if (estimator::g_estimator == nullptr)
+ errx(1, "not running");
+
+ delete estimator::g_estimator;
+ estimator::g_estimator = nullptr;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (estimator::g_estimator) {
+ warnx("running");
+
+ print_status();
+
+ exit(0);
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ warnx("unrecognized command");
+ return 1;
+}
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c
new file mode 100644
index 000000000..6138ef39c
--- /dev/null
+++ b/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file fw_att_pos_estimator_params.c
+ *
+ * Parameters defined by the attitude and position estimator task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Estimator parameters, accessible via MAVLink
+ *
+ */
+
+/**
+ * Velocity estimate delay
+ *
+ * The delay in milliseconds of the velocity estimate from GPS.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230);
+
+/**
+ * Position estimate delay
+ *
+ * The delay in milliseconds of the position estimate from GPS.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210);
+
+/**
+ * Height estimate delay
+ *
+ * The delay in milliseconds of the height estimate from the barometer.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350);
+
+/**
+ * Mag estimate delay
+ *
+ * The delay in milliseconds of the magnetic field estimate from
+ * the magnetometer.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30);
+
+/**
+ * True airspeeed estimate delay
+ *
+ * The delay in milliseconds of the airspeed estimate.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
+
+/**
+ * GPS vs. barometric altitude update weight
+ *
+ * RE-CHECK this.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
+
diff --git a/src/modules/fw_att_pos_estimator/module.mk b/src/modules/fw_att_pos_estimator/module.mk
new file mode 100644
index 000000000..c992959e0
--- /dev/null
+++ b/src/modules/fw_att_pos_estimator/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Main Attitude and Position Estimator for Fixed Wing Aircraft
+#
+
+MODULE_COMMAND = fw_att_pos_estimator
+
+SRCS = fw_att_pos_estimator_main.cpp \
+ fw_att_pos_estimator_params.c \
+ estimator.cpp
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 1dbe56495..73a7e132b 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -387,7 +387,6 @@ handle_message(mavlink_message_t *msg)
hil_sensors.gyro_rad_s[0] = imu.xgyro;
hil_sensors.gyro_rad_s[1] = imu.ygyro;
hil_sensors.gyro_rad_s[2] = imu.zgyro;
- hil_sensors.gyro_counter = hil_counter;
/* accelerometer */
static const float mg2ms2 = 9.8f / 1000.0f;
@@ -399,7 +398,7 @@ handle_message(mavlink_message_t *msg)
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
hil_sensors.accelerometer_mode = 0; // TODO what is this?
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
- hil_sensors.accelerometer_counter = hil_counter;
+ hil_sensors.accelerometer_timestamp = hil_sensors.timestamp;
/* adc */
hil_sensors.adc_voltage_v[0] = 0.0f;
@@ -417,17 +416,17 @@ handle_message(mavlink_message_t *msg)
hil_sensors.magnetometer_range_ga = 32.7f; // int16
hil_sensors.magnetometer_mode = 0; // TODO what is this
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
- hil_sensors.magnetometer_counter = hil_counter;
+ hil_sensors.magnetometer_timestamp = hil_sensors.timestamp;
/* baro */
hil_sensors.baro_pres_mbar = imu.abs_pressure;
hil_sensors.baro_alt_meter = imu.pressure_alt;
hil_sensors.baro_temp_celcius = imu.temperature;
- hil_sensors.baro_counter = hil_counter;
+ hil_sensors.baro_timestamp = hil_sensors.timestamp;
/* differential pressure */
hil_sensors.differential_pressure_pa = imu.diff_pressure * 1e2f; //from hPa to Pa
- hil_sensors.differential_pressure_counter = hil_counter;
+ hil_sensors.differential_pressure_timestamp = hil_sensors.timestamp;
/* airspeed from differential pressure, ambient pressure and temp */
struct airspeed_s airspeed;
@@ -830,7 +829,7 @@ receive_thread(void *arg)
while (!thread_should_exit) {
if (poll(fds, 1, timeout) > 0) {
- if (nread < sizeof(buf)) {
+ if (nread < (ssize_t)sizeof(buf)) {
/* to avoid reading very small chunks wait for data before reading */
usleep(1000);
}
diff --git a/src/modules/mavlink/orb_listener.c b/src/modules/mavlink/orb_listener.c
index d7243c623..a70ee7d81 100644
--- a/src/modules/mavlink/orb_listener.c
+++ b/src/modules/mavlink/orb_listener.c
@@ -182,33 +182,33 @@ l_sensor_combined(const struct listener *l)
/* mark individual fields as changed */
uint16_t fields_updated = 0;
- static unsigned accel_counter = 0;
- static unsigned gyro_counter = 0;
- static unsigned mag_counter = 0;
- static unsigned baro_counter = 0;
+ static hrt_abstime accel_counter = 0;
+ static hrt_abstime gyro_counter = 0;
+ static hrt_abstime mag_counter = 0;
+ static hrt_abstime baro_counter = 0;
- if (accel_counter != raw.accelerometer_counter) {
+ if (accel_counter != raw.accelerometer_timestamp) {
/* mark first three dimensions as changed */
fields_updated |= (1 << 0) | (1 << 1) | (1 << 2);
- accel_counter = raw.accelerometer_counter;
+ accel_counter = raw.accelerometer_timestamp;
}
- if (gyro_counter != raw.gyro_counter) {
+ if (gyro_counter != raw.timestamp) {
/* mark second group dimensions as changed */
fields_updated |= (1 << 3) | (1 << 4) | (1 << 5);
- gyro_counter = raw.gyro_counter;
+ gyro_counter = raw.timestamp;
}
- if (mag_counter != raw.magnetometer_counter) {
+ if (mag_counter != raw.magnetometer_timestamp) {
/* mark third group dimensions as changed */
fields_updated |= (1 << 6) | (1 << 7) | (1 << 8);
- mag_counter = raw.magnetometer_counter;
+ mag_counter = raw.magnetometer_timestamp;
}
- if (baro_counter != raw.baro_counter) {
+ if (baro_counter != raw.baro_timestamp) {
/* mark last group dimensions as changed */
fields_updated |= (1 << 9) | (1 << 11) | (1 << 12);
- baro_counter = raw.baro_counter;
+ baro_counter = raw.baro_timestamp;
}
if (gcs_link)
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 a14354138..368fa6ee2 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -200,8 +200,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
bool landed = true;
hrt_abstime landed_time = 0;
- uint32_t accel_counter = 0;
- uint32_t baro_counter = 0;
+ hrt_abstime accel_timestamp = 0;
+ hrt_abstime baro_timestamp = 0;
bool ref_inited = false;
hrt_abstime ref_init_start = 0;
@@ -310,8 +310,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (fds_init[0].revents & POLLIN) {
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- if (wait_baro && sensor.baro_counter != baro_counter) {
- baro_counter = sensor.baro_counter;
+ if (wait_baro && sensor.baro_timestamp != baro_timestamp) {
+ baro_timestamp = sensor.baro_timestamp;
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
@@ -384,7 +384,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (updated) {
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- if (sensor.accelerometer_counter != accel_counter) {
+ if (sensor.accelerometer_timestamp != accel_timestamp) {
if (att.R_valid) {
/* correct accel bias */
sensor.accelerometer_m_s2[0] -= acc_bias[0];
@@ -408,13 +408,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memset(corr_acc, 0, sizeof(corr_acc));
}
- accel_counter = sensor.accelerometer_counter;
+ accel_timestamp = sensor.accelerometer_timestamp;
accel_updates++;
}
- if (sensor.baro_counter != baro_counter) {
+ if (sensor.baro_timestamp != baro_timestamp) {
corr_baro = baro_offset - sensor.baro_alt_meter - z_est[0];
- baro_counter = sensor.baro_counter;
+ baro_timestamp = sensor.baro_timestamp;
baro_updates++;
}
}
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 1365d9e70..c4cb2f8f5 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -977,11 +977,11 @@ int sdlog2_thread_main(int argc, char *argv[])
pthread_cond_init(&logbuffer_cond, NULL);
/* track changes in sensor_combined topic */
- uint16_t gyro_counter = 0;
- uint16_t accelerometer_counter = 0;
- uint16_t magnetometer_counter = 0;
- uint16_t baro_counter = 0;
- uint16_t differential_pressure_counter = 0;
+ hrt_abstime gyro_timestamp = 0;
+ hrt_abstime accelerometer_timestamp = 0;
+ hrt_abstime magnetometer_timestamp = 0;
+ hrt_abstime barometer_timestamp = 0;
+ hrt_abstime differential_pressure_timestamp = 0;
/* track changes in distance status */
bool dist_bottom_present = false;
@@ -1097,28 +1097,28 @@ int sdlog2_thread_main(int argc, char *argv[])
bool write_IMU = false;
bool write_SENS = false;
- if (buf.sensor.gyro_counter != gyro_counter) {
- gyro_counter = buf.sensor.gyro_counter;
+ if (buf.sensor.timestamp != gyro_timestamp) {
+ gyro_timestamp = buf.sensor.timestamp;
write_IMU = true;
}
- if (buf.sensor.accelerometer_counter != accelerometer_counter) {
- accelerometer_counter = buf.sensor.accelerometer_counter;
+ if (buf.sensor.accelerometer_timestamp != accelerometer_timestamp) {
+ accelerometer_timestamp = buf.sensor.accelerometer_timestamp;
write_IMU = true;
}
- if (buf.sensor.magnetometer_counter != magnetometer_counter) {
- magnetometer_counter = buf.sensor.magnetometer_counter;
+ if (buf.sensor.magnetometer_timestamp != magnetometer_timestamp) {
+ magnetometer_timestamp = buf.sensor.magnetometer_timestamp;
write_IMU = true;
}
- if (buf.sensor.baro_counter != baro_counter) {
- baro_counter = buf.sensor.baro_counter;
+ if (buf.sensor.baro_timestamp != barometer_timestamp) {
+ barometer_timestamp = buf.sensor.baro_timestamp;
write_SENS = true;
}
- if (buf.sensor.differential_pressure_counter != differential_pressure_counter) {
- differential_pressure_counter = buf.sensor.differential_pressure_counter;
+ if (buf.sensor.differential_pressure_timestamp != differential_pressure_timestamp) {
+ differential_pressure_timestamp = buf.sensor.differential_pressure_timestamp;
write_SENS = true;
}
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index b176d7417..dc5bd95c6 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -36,6 +36,8 @@
* Sensor readout process.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include <nuttx/config.h>
@@ -940,7 +942,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw)
raw.accelerometer_raw[1] = accel_report.y_raw;
raw.accelerometer_raw[2] = accel_report.z_raw;
- raw.accelerometer_counter++;
+ raw.accelerometer_timestamp = accel_report.timestamp;
}
}
@@ -966,7 +968,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw)
raw.gyro_raw[1] = gyro_report.y_raw;
raw.gyro_raw[2] = gyro_report.z_raw;
- raw.gyro_counter++;
+ raw.timestamp = gyro_report.timestamp;
}
}
@@ -996,7 +998,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
raw.magnetometer_raw[1] = mag_report.y_raw;
raw.magnetometer_raw[2] = mag_report.z_raw;
- raw.magnetometer_counter++;
+ raw.magnetometer_timestamp = mag_report.timestamp;
}
}
@@ -1014,7 +1016,7 @@ Sensors::baro_poll(struct sensor_combined_s &raw)
raw.baro_alt_meter = _barometer.altitude; // Altitude in meters
raw.baro_temp_celcius = _barometer.temperature; // Temperature in degrees celcius
- raw.baro_counter++;
+ raw.baro_timestamp = _barometer.timestamp;
}
}
@@ -1028,7 +1030,7 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw)
orb_copy(ORB_ID(differential_pressure), _diff_pres_sub, &_diff_pres);
raw.differential_pressure_pa = _diff_pres.differential_pressure_pa;
- raw.differential_pressure_counter++;
+ raw.differential_pressure_timestamp = _diff_pres.timestamp;
_airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa);
_airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar * 1e2f,
@@ -1592,9 +1594,6 @@ Sensors::task_main()
/* check parameters for updates */
parameter_update_poll();
- /* store the time closest to all measurements (this is bogus, sensor timestamps should be propagated...) */
- raw.timestamp = hrt_absolute_time();
-
/* copy most recent sensor data */
gyro_poll(raw);
accel_poll(raw);
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h
index 11332d7a7..628824efa 100644
--- a/src/modules/uORB/topics/esc_status.h
+++ b/src/modules/uORB/topics/esc_status.h
@@ -60,7 +60,7 @@
enum ESC_VENDOR {
ESC_VENDOR_GENERIC = 0, /**< generic ESC */
ESC_VENDOR_MIKROKOPTER, /**< Mikrokopter */
- ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
+ ESC_VENDOR_GRAUPNER_HOTT /**< Graupner HoTT ESC */
};
enum ESC_CONNECTION_TYPE {
@@ -79,16 +79,15 @@ enum ESC_CONNECTION_TYPE {
/**
* Electronic speed controller status.
*/
-struct esc_status_s
-{
+struct esc_status_s {
/* use of a counter and timestamp recommended (but not necessary) */
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
-
+
uint8_t esc_count; /**< number of connected ESCs */
enum ESC_CONNECTION_TYPE esc_connectiontype; /**< how ESCs connected to the system */
-
+
struct {
uint16_t esc_address; /**< Address of current ESC (in most cases 1-8 / must be set by driver) */
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */
diff --git a/src/modules/uORB/topics/filtered_bottom_flow.h b/src/modules/uORB/topics/filtered_bottom_flow.h
index ab6de2613..c5d545542 100644
--- a/src/modules/uORB/topics/filtered_bottom_flow.h
+++ b/src/modules/uORB/topics/filtered_bottom_flow.h
@@ -53,8 +53,7 @@
/**
* Filtered bottom flow in bodyframe.
*/
-struct filtered_bottom_flow_s
-{
+struct filtered_bottom_flow_s {
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
float sumx; /**< Integrated bodyframe x flow in meters */
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 194e2ed0c..9594c4c6a 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -77,8 +77,7 @@ enum ORIGIN {
* This is the position the MAV is heading towards. If it of type loiter,
* the MAV is circling around it with the given loiter radius in meters.
*/
-struct mission_item_s
-{
+struct mission_item_s {
bool altitude_is_relative; /**< true if altitude is relative from start point */
double lat; /**< latitude in degrees */
double lon; /**< longitude in degrees */
diff --git a/src/modules/uORB/topics/navigation_capabilities.h b/src/modules/uORB/topics/navigation_capabilities.h
index 391756f99..7a5ae9891 100644
--- a/src/modules/uORB/topics/navigation_capabilities.h
+++ b/src/modules/uORB/topics/navigation_capabilities.h
@@ -52,12 +52,12 @@
* Airspeed
*/
struct navigation_capabilities_s {
- float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
+ float turn_distance; /**< the optimal distance to a waypoint to switch to the next */
- /* Landing parameters: see fw_pos_control_l1/landingslope.h */
- float landing_horizontal_slope_displacement;
- float landing_slope_angle_rad;
- float landing_flare_length;
+ /* Landing parameters: see fw_pos_control_l1/landingslope.h */
+ float landing_horizontal_slope_displacement;
+ float landing_slope_angle_rad;
+ float landing_flare_length;
};
/**
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index 7901b930a..68d3e494b 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -45,12 +45,11 @@
/**
* Off-board control inputs.
- *
+ *
* Typically sent by a ground control station / joystick or by
* some off-board controller via C or SIMULINK.
*/
-enum OFFBOARD_CONTROL_MODE
-{
+enum OFFBOARD_CONTROL_MODE {
OFFBOARD_CONTROL_MODE_DIRECT = 0,
OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index cf1ddfc38..34aaa30dd 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -54,24 +54,24 @@
enum SETPOINT_TYPE
{
- SETPOINT_TYPE_NORMAL = 0, /**< normal setpoint */
- SETPOINT_TYPE_LOITER, /**< loiter setpoint */
- SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
+ SETPOINT_TYPE_NORMAL = 0, /**< normal setpoint */
+ SETPOINT_TYPE_LOITER, /**< loiter setpoint */
+ SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, vehicle must descend until landing */
SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
};
struct position_setpoint_s
{
- bool valid; /**< true if setpoint is valid */
+ bool valid; /**< true if setpoint is valid */
enum SETPOINT_TYPE type; /**< setpoint type to adjust behavior of position controller */
- double lat; /**< latitude, in deg */
- double lon; /**< longitude, in deg */
- float alt; /**< altitude AMSL, in m */
- float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
+ double lat; /**< latitude, in deg */
+ double lon; /**< longitude, in deg */
+ float alt; /**< altitude AMSL, in m */
+ float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
float loiter_radius; /**< loiter radius (only for fixed wing), in m */
int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */
- float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
+ float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
};
/**
@@ -85,7 +85,7 @@ struct position_setpoint_triplet_s
struct position_setpoint_s current;
struct position_setpoint_s next;
- nav_state_t nav_state; /**< navigation state */
+ nav_state_t nav_state; /**< navigation state */
};
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 086b2ef15..6eb20efd1 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -52,29 +52,28 @@
*/
#define RC_CHANNELS_MAPPED_MAX 15
-/**
+/**
* This defines the mapping of the RC functions.
* The value assigned to the specific function corresponds to the entry of
* the channel array chan[].
*/
-enum RC_CHANNELS_FUNCTION
-{
- THROTTLE = 0,
- ROLL = 1,
- PITCH = 2,
- YAW = 3,
- MODE = 4,
- RETURN = 5,
- ASSISTED = 6,
- MISSION = 7,
- OFFBOARD_MODE = 8,
- FLAPS = 9,
- AUX_1 = 10,
- AUX_2 = 11,
- AUX_3 = 12,
- AUX_4 = 13,
- AUX_5 = 14,
- RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
+enum RC_CHANNELS_FUNCTION {
+ THROTTLE = 0,
+ ROLL = 1,
+ PITCH = 2,
+ YAW = 3,
+ MODE = 4,
+ RETURN = 5,
+ ASSISTED = 6,
+ MISSION = 7,
+ OFFBOARD_MODE = 8,
+ FLAPS = 9,
+ AUX_1 = 10,
+ AUX_2 = 11,
+ AUX_3 = 12,
+ AUX_4 = 13,
+ AUX_5 = 14,
+ RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
/**
@@ -85,16 +84,16 @@ enum RC_CHANNELS_FUNCTION
struct rc_channels_s {
uint64_t timestamp; /**< In microseconds since boot time. */
- uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
- struct {
- float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
- } chan[RC_CHANNELS_MAPPED_MAX];
- uint8_t chan_count; /**< number of valid channels */
+ uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
+ struct {
+ float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
+ } chan[RC_CHANNELS_MAPPED_MAX];
+ uint8_t chan_count; /**< number of valid channels */
- /*String array to store the names of the functions*/
- char function_name[RC_CHANNELS_FUNCTION_MAX][20];
- int8_t function[RC_CHANNELS_FUNCTION_MAX];
- uint8_t rssi; /**< Overall receive signal strength */
+ /*String array to store the names of the functions*/
+ char function_name[RC_CHANNELS_FUNCTION_MAX][20];
+ int8_t function[RC_CHANNELS_FUNCTION_MAX];
+ uint8_t rssi; /**< Overall receive signal strength */
}; /**< radio control channels. */
/**
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index ad164555e..92812efd4 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -77,34 +77,33 @@ struct sensor_combined_s {
/* NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes Change with consideration only */
- uint64_t timestamp; /**< Timestamp in microseconds since boot */
+ uint64_t timestamp; /**< Timestamp in microseconds since boot, from gyro */
int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity */
- uint16_t gyro_counter; /**< Number of raw measurments taken */
float gyro_rad_s[3]; /**< Angular velocity in radian per seconds */
-
+
int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame */
- uint32_t accelerometer_counter; /**< Number of raw acc measurements taken */
float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
int accelerometer_mode; /**< Accelerometer measurement mode */
float accelerometer_range_m_s2; /**< Accelerometer measurement range in m/s^2 */
+ uint64_t accelerometer_timestamp; /**< Accelerometer timestamp */
int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */
float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
int magnetometer_mode; /**< Magnetometer measurement mode */
float magnetometer_range_ga; /**< ± measurement range in Gauss */
float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */
- uint32_t magnetometer_counter; /**< Number of raw mag measurements taken */
-
+ uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */
+
float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
float baro_alt_meter; /**< Altitude, already temp. comp. */
float baro_temp_celcius; /**< Temperature in degrees celsius */
float adc_voltage_v[4]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
float mcu_temp_celcius; /**< Internal temperature measurement of MCU */
- uint32_t baro_counter; /**< Number of raw baro measurements taken */
+ uint64_t baro_timestamp; /**< Barometer timestamp */
- float differential_pressure_pa; /**< Airspeed sensor differential pressure */
- uint32_t differential_pressure_counter; /**< Number of raw differential pressure measurements taken */
+ float differential_pressure_pa; /**< Airspeed sensor differential pressure */
+ uint64_t differential_pressure_timestamp; /**< Last measurement timestamp */
};
/**
diff --git a/src/modules/uORB/topics/subsystem_info.h b/src/modules/uORB/topics/subsystem_info.h
index cfe0bf69e..d3a7ce10d 100644
--- a/src/modules/uORB/topics/subsystem_info.h
+++ b/src/modules/uORB/topics/subsystem_info.h
@@ -50,8 +50,7 @@
#include <stdbool.h>
#include "../uORB.h"
-enum SUBSYSTEM_TYPE
-{
+enum SUBSYSTEM_TYPE {
SUBSYSTEM_TYPE_GYRO = 1,
SUBSYSTEM_TYPE_ACC = 2,
SUBSYSTEM_TYPE_MAG = 4,
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 5192d4d58..76693c46e 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -44,10 +44,10 @@
#include "../uORB.h"
enum TELEMETRY_STATUS_RADIO_TYPE {
- TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
- TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
- TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
- TELEMETRY_STATUS_RADIO_TYPE_WIRE
+ TELEMETRY_STATUS_RADIO_TYPE_GENERIC = 0,
+ TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO,
+ TELEMETRY_STATUS_RADIO_TYPE_UBIQUITY_BULLET,
+ TELEMETRY_STATUS_RADIO_TYPE_WIRE
};
/**
@@ -57,14 +57,14 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
struct telemetry_status_s {
uint64_t timestamp;
- enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
- uint8_t rssi; /**< local signal strength */
- uint8_t remote_rssi; /**< remote signal strength */
- uint16_t rxerrors; /**< receive errors */
- uint16_t fixed; /**< count of error corrected packets */
- uint8_t noise; /**< background noise level */
- uint8_t remote_noise; /**< remote background noise level */
- uint8_t txbuf; /**< how full the tx buffer is as a percentage */
+ enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
+ uint8_t rssi; /**< local signal strength */
+ uint8_t remote_rssi; /**< remote signal strength */
+ uint16_t rxerrors; /**< receive errors */
+ uint16_t fixed; /**< count of error corrected packets */
+ uint8_t noise; /**< background noise level */
+ uint8_t remote_noise; /**< remote background noise level */
+ uint8_t txbuf; /**< how full the tx buffer is as a percentage */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
index 7596f944f..d526a8ff2 100644
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -52,8 +52,7 @@
/**
* vehicle attitude setpoint.
*/
-struct vehicle_attitude_setpoint_s
-{
+struct vehicle_attitude_setpoint_s {
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
float roll_body; /**< body angle in NED frame */
diff --git a/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
index fbfab09f3..fd1ade671 100644
--- a/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_bodyframe_speed_setpoint.h
@@ -48,8 +48,7 @@
* @{
*/
-struct vehicle_bodyframe_speed_setpoint_s
-{
+struct vehicle_bodyframe_speed_setpoint_s {
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
float vx; /**< in m/s */
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index e6e4743c6..c21a29b13 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -51,43 +51,42 @@
* Should contain all commands from MAVLink's VEHICLE_CMD ENUM,
* but can contain additional ones.
*/
-enum VEHICLE_CMD
-{
- VEHICLE_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- VEHICLE_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- VEHICLE_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
- VEHICLE_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
- VEHICLE_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
- VEHICLE_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
- VEHICLE_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- VEHICLE_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
- VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
- VEHICLE_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
- VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
- VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
- VEHICLE_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
- VEHICLE_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
- VEHICLE_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
- VEHICLE_CMD_ENUM_END=501, /* | */
+enum VEHICLE_CMD {
+ VEHICLE_CMD_NAV_WAYPOINT = 16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_UNLIM = 17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_TURNS = 18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_TIME = 19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_RETURN_TO_LAUNCH = 20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_LAND = 21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_DELAY = 112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_CHANGE_ALT = 113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
+ VEHICLE_CMD_CONDITION_DISTANCE = 114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_YAW = 115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_LAST = 159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_MODE = 176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_JUMP = 177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_CHANGE_SPEED = 178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_HOME = 179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_DO_SET_PARAMETER = 180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_RELAY = 181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_REPEAT_RELAY = 182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_SERVO = 183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_REPEAT_SERVO = 184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_CONTROL_VIDEO = 200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_LAST = 240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_CALIBRATION = 241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
+ VEHICLE_CMD_PREFLIGHT_STORAGE = 245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
+ VEHICLE_CMD_OVERRIDE_GOTO = 252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
+ VEHICLE_CMD_MISSION_START = 300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
+ VEHICLE_CMD_COMPONENT_ARM_DISARM = 400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
+ VEHICLE_CMD_START_RX_PAIR = 500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */
+ VEHICLE_CMD_ENUM_END = 501, /* | */
};
/**
@@ -96,14 +95,13 @@ enum VEHICLE_CMD
* Should contain all of MAVLink's VEHICLE_CMD_RESULT values
* but can contain additional ones.
*/
-enum VEHICLE_CMD_RESULT
-{
- VEHICLE_CMD_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
- VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
- VEHICLE_CMD_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
- VEHICLE_CMD_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
- VEHICLE_CMD_RESULT_FAILED=4, /* Command executed, but failed | */
- VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
+enum VEHICLE_CMD_RESULT {
+ VEHICLE_CMD_RESULT_ACCEPTED = 0, /* Command ACCEPTED and EXECUTED | */
+ VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED = 1, /* Command TEMPORARY REJECTED/DENIED | */
+ VEHICLE_CMD_RESULT_DENIED = 2, /* Command PERMANENTLY DENIED | */
+ VEHICLE_CMD_RESULT_UNSUPPORTED = 3, /* Command UNKNOWN/UNSUPPORTED | */
+ VEHICLE_CMD_RESULT_FAILED = 4, /* Command executed, but failed | */
+ VEHICLE_CMD_RESULT_ENUM_END = 5, /* | */
};
/**
@@ -111,8 +109,7 @@ enum VEHICLE_CMD_RESULT
* @{
*/
-struct vehicle_command_s
-{
+struct vehicle_command_s {
float param1; /**< Parameter 1, as defined by MAVLink VEHICLE_CMD enum. */
float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
diff --git a/src/modules/uORB/topics/vehicle_control_debug.h b/src/modules/uORB/topics/vehicle_control_debug.h
index 6184284a4..2a45eaccc 100644
--- a/src/modules/uORB/topics/vehicle_control_debug.h
+++ b/src/modules/uORB/topics/vehicle_control_debug.h
@@ -47,8 +47,7 @@
* @addtogroup topics
* @{
*/
-struct vehicle_control_debug_s
-{
+struct vehicle_control_debug_s {
uint64_t timestamp; /**< in microseconds since system start */
float roll_p; /**< roll P control part */
@@ -77,9 +76,9 @@ struct vehicle_control_debug_s
}; /**< vehicle_control_debug */
- /**
- * @}
- */
+/**
+* @}
+*/
/* register this as object request broker structure */
ORB_DECLARE(vehicle_control_debug);
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 7cbb37cd8..ea554006f 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -38,8 +34,13 @@
/**
* @file vehicle_control_mode.h
* Definition of the vehicle_control_mode uORB topic.
- *
+ *
* All control apps should depend their actions based on the flags set here.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef VEHICLE_CONTROL_MODE
@@ -61,8 +62,7 @@
* Encodes the complete system state and is set by the commander app.
*/
-struct vehicle_control_mode_s
-{
+struct vehicle_control_mode_s {
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
bool flag_armed;
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index ff9e98e1c..adcd028f0 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file vehicle_global_position.h
* Definition of the global fused WGS84 position uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef VEHICLE_GLOBAL_POSITION_T_H_
@@ -59,8 +60,7 @@
* estimator, which will take more sources of information into account than just GPS,
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
*/
-struct vehicle_global_position_s
-{
+struct vehicle_global_position_s {
uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
bool global_valid; /**< true if position satisfies validity criteria of estimator */
diff --git a/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h b/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h
index 73961cdfe..5dac877d0 100644
--- a/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_global_velocity_setpoint.h
@@ -47,8 +47,7 @@
* @{
*/
-struct vehicle_global_velocity_setpoint_s
-{
+struct vehicle_global_velocity_setpoint_s {
float vx; /**< in m/s NED */
float vy; /**< in m/s NED */
float vz; /**< in m/s NED */
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 1639a08c2..794c3f8bc 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -53,13 +53,12 @@
/**
* GPS position in WGS84 coordinates.
*/
-struct vehicle_gps_position_s
-{
+struct vehicle_gps_position_s {
uint64_t timestamp_position; /**< Timestamp for position information */
int32_t lat; /**< Latitude in 1E-7 degrees */
int32_t lon; /**< Longitude in 1E-7 degrees */
int32_t alt; /**< Altitude in 1E-3 meters (millimeters) above MSL */
-
+
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
float p_variance_m; /**< position accuracy estimate m */
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index d567f2e02..db9637cd9 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -52,8 +52,7 @@
/**
* Fused local position in NED.
*/
-struct vehicle_local_position_s
-{
+struct vehicle_local_position_s {
uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
bool xy_valid; /**< true if x and y are valid */
bool z_valid; /**< true if z is valid */
diff --git a/src/modules/uORB/topics/vehicle_local_position_setpoint.h b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
index d24d81e3a..8988a0330 100644
--- a/src/modules/uORB/topics/vehicle_local_position_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
@@ -49,8 +49,7 @@
* @{
*/
-struct vehicle_local_position_setpoint_s
-{
+struct vehicle_local_position_setpoint_s {
float x; /**< in meters NED */
float y; /**< in meters NED */
float z; /**< in meters NED */
diff --git a/src/modules/uORB/topics/vehicle_rates_setpoint.h b/src/modules/uORB/topics/vehicle_rates_setpoint.h
index 46e62c4b7..9f8b412a7 100644
--- a/src/modules/uORB/topics/vehicle_rates_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_rates_setpoint.h
@@ -47,8 +47,7 @@
* @addtogroup topics
* @{
*/
-struct vehicle_rates_setpoint_s
-{
+struct vehicle_rates_setpoint_s {
uint64_t timestamp; /**< in microseconds since system start */
float roll; /**< body angular rates in NED frame */
@@ -58,9 +57,9 @@ struct vehicle_rates_setpoint_s
}; /**< vehicle_rates_setpoint */
- /**
- * @}
- */
+/**
+* @}
+*/
/* register this as object request broker structure */
ORB_DECLARE(vehicle_rates_setpoint);
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 5d40554fd..56be4d241 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -131,31 +131,31 @@ enum VEHICLE_MODE_FLAG {
* Should match 1:1 MAVLink's MAV_TYPE ENUM
*/
enum VEHICLE_TYPE {
- VEHICLE_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
- VEHICLE_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
- VEHICLE_TYPE_QUADROTOR=2, /* Quadrotor | */
- VEHICLE_TYPE_COAXIAL=3, /* Coaxial helicopter | */
- VEHICLE_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
- VEHICLE_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
- VEHICLE_TYPE_GCS=6, /* Operator control unit / ground control station | */
- VEHICLE_TYPE_AIRSHIP=7, /* Airship, controlled | */
- VEHICLE_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
- VEHICLE_TYPE_ROCKET=9, /* Rocket | */
- VEHICLE_TYPE_GROUND_ROVER=10, /* Ground rover | */
- VEHICLE_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
- VEHICLE_TYPE_SUBMARINE=12, /* Submarine | */
- VEHICLE_TYPE_HEXAROTOR=13, /* Hexarotor | */
- VEHICLE_TYPE_OCTOROTOR=14, /* Octorotor | */
- VEHICLE_TYPE_TRICOPTER=15, /* Octorotor | */
- VEHICLE_TYPE_FLAPPING_WING=16, /* Flapping wing | */
- VEHICLE_TYPE_KITE=17, /* Kite | */
- VEHICLE_TYPE_ENUM_END=18, /* | */
+ VEHICLE_TYPE_GENERIC = 0, /* Generic micro air vehicle. | */
+ VEHICLE_TYPE_FIXED_WING = 1, /* Fixed wing aircraft. | */
+ VEHICLE_TYPE_QUADROTOR = 2, /* Quadrotor | */
+ VEHICLE_TYPE_COAXIAL = 3, /* Coaxial helicopter | */
+ VEHICLE_TYPE_HELICOPTER = 4, /* Normal helicopter with tail rotor. | */
+ VEHICLE_TYPE_ANTENNA_TRACKER = 5, /* Ground installation | */
+ VEHICLE_TYPE_GCS = 6, /* Operator control unit / ground control station | */
+ VEHICLE_TYPE_AIRSHIP = 7, /* Airship, controlled | */
+ VEHICLE_TYPE_FREE_BALLOON = 8, /* Free balloon, uncontrolled | */
+ VEHICLE_TYPE_ROCKET = 9, /* Rocket | */
+ VEHICLE_TYPE_GROUND_ROVER = 10, /* Ground rover | */
+ VEHICLE_TYPE_SURFACE_BOAT = 11, /* Surface vessel, boat, ship | */
+ VEHICLE_TYPE_SUBMARINE = 12, /* Submarine | */
+ VEHICLE_TYPE_HEXAROTOR = 13, /* Hexarotor | */
+ VEHICLE_TYPE_OCTOROTOR = 14, /* Octorotor | */
+ VEHICLE_TYPE_TRICOPTER = 15, /* Octorotor | */
+ VEHICLE_TYPE_FLAPPING_WING = 16, /* Flapping wing | */
+ VEHICLE_TYPE_KITE = 17, /* Kite | */
+ VEHICLE_TYPE_ENUM_END = 18, /* | */
};
enum VEHICLE_BATTERY_WARNING {
- VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
- VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
- VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
+ VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
+ VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
+ VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
};
/**
@@ -168,8 +168,7 @@ enum VEHICLE_BATTERY_WARNING {
*
* Encodes the complete system state and is set by the commander app.
*/
-struct vehicle_status_s
-{
+struct vehicle_status_s {
/* use of a counter and timestamp recommended (but not necessary) */
uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
@@ -219,7 +218,7 @@ struct vehicle_status_s
uint32_t onboard_control_sensors_present;
uint32_t onboard_control_sensors_enabled;
uint32_t onboard_control_sensors_health;
-
+
float load; /**< processor load from 0 to 1 */
float battery_voltage;
float battery_current;
diff --git a/src/modules/uORB/topics/vehicle_vicon_position.h b/src/modules/uORB/topics/vehicle_vicon_position.h
index 0822fa89a..e19a34a5d 100644
--- a/src/modules/uORB/topics/vehicle_vicon_position.h
+++ b/src/modules/uORB/topics/vehicle_vicon_position.h
@@ -52,8 +52,7 @@
/**
* Fused local position in NED.
*/
-struct vehicle_vicon_position_s
-{
+struct vehicle_vicon_position_s {
uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
bool valid; /**< true if position satisfies validity criteria of estimator */