aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-07-15 22:07:03 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-07-15 22:07:03 +0200
commite696ed5509d001e181c33a2379d634e76190c42a (patch)
tree8fd3e88c0782ceb90e6b9589daa1290d548058fd /src/modules
parent79aa600d29c66e4619aacf73e71e51df13560205 (diff)
parent619433d36911b9c3923bae666d3632beb713935f (diff)
downloadpx4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.tar.gz
px4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.tar.bz2
px4-firmware-e696ed5509d001e181c33a2379d634e76190c42a.zip
Merged master
Diffstat (limited to 'src/modules')
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp30
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c15
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h1
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp21
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp12
-rw-r--r--src/modules/commander/accelerometer_calibration.h3
-rw-r--r--src/modules/commander/airspeed_calibration.cpp132
-rw-r--r--src/modules/commander/airspeed_calibration.h2
-rw-r--r--src/modules/commander/baro_calibration.cpp2
-rw-r--r--src/modules/commander/baro_calibration.h2
-rw-r--r--src/modules/commander/calibration_messages.h3
-rw-r--r--src/modules/commander/calibration_routines.cpp12
-rw-r--r--src/modules/commander/calibration_routines.h3
-rw-r--r--src/modules/commander/commander.cpp957
-rw-r--r--src/modules/commander/commander_helper.cpp16
-rw-r--r--src/modules/commander/commander_helper.h9
-rw-r--r--src/modules/commander/commander_params.c13
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp213
-rw-r--r--src/modules/commander/mag_calibration.h2
-rw-r--r--src/modules/commander/px4_custom_mode.h2
-rw-r--r--src/modules/commander/state_machine_helper.cpp692
-rw-r--r--src/modules/commander/state_machine_helper.h28
-rw-r--r--src/modules/dataman/dataman.c57
-rw-r--r--src/modules/dataman/dataman.h18
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp1014
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_21states.cpp2142
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_21states.h247
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp (renamed from src/modules/ekf_att_pos_estimator/estimator.cpp)1243
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.h (renamed from src/modules/ekf_att_pos_estimator/estimator.h)122
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_utilities.cpp162
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_utilities.h89
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk5
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp39
-rw-r--r--src/modules/fw_att_control/module.mk2
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp350
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.cpp16
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.h8
-rw-r--r--src/modules/fw_pos_control_l1/module.mk9
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/limitoverride.cpp71
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/limitoverride.h107
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.cpp313
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.h155
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h220
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs_params.c419
-rw-r--r--src/modules/gpio_led/gpio_led.c9
-rw-r--r--src/modules/mavlink/mavlink_commands.cpp35
-rw-r--r--src/modules/mavlink/mavlink_commands.h2
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp423
-rw-r--r--src/modules/mavlink/mavlink_ftp.h227
-rw-r--r--src/modules/mavlink/mavlink_main.cpp998
-rw-r--r--src/modules/mavlink/mavlink_main.h279
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp1227
-rw-r--r--src/modules/mavlink/mavlink_messages.h15
-rw-r--r--src/modules/mavlink/mavlink_mission.cpp828
-rw-r--r--src/modules/mavlink/mavlink_mission.h177
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.cpp55
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.h30
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp196
-rw-r--r--src/modules/mavlink/mavlink_receiver.h17
-rw-r--r--src/modules/mavlink/mavlink_stream.cpp6
-rw-r--r--src/modules/mavlink/mavlink_stream.h23
-rw-r--r--src/modules/mavlink/module.mk4
-rw-r--r--src/modules/mavlink/waypoints.h111
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp17
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp110
-rw-r--r--src/modules/navigator/geofence.cpp9
-rw-r--r--src/modules/navigator/loiter.cpp93
-rw-r--r--src/modules/navigator/loiter.h (renamed from src/modules/navigator/navigator_state.h)45
-rw-r--r--src/modules/navigator/mission.cpp618
-rw-r--r--src/modules/navigator/mission.h163
-rw-r--r--src/modules/navigator/mission_block.cpp251
-rw-r--r--src/modules/navigator/mission_block.h (renamed from src/modules/navigator/navigator_mission.h)97
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp3
-rw-r--r--src/modules/navigator/mission_params.c84
-rw-r--r--src/modules/navigator/module.mk11
-rw-r--r--src/modules/navigator/navigator.h226
-rw-r--r--src/modules/navigator/navigator_main.cpp1428
-rw-r--r--src/modules/navigator/navigator_mission.cpp319
-rw-r--r--src/modules/navigator/navigator_mode.cpp95
-rw-r--r--src/modules/navigator/navigator_mode.h93
-rw-r--r--src/modules/navigator/navigator_params.c95
-rw-r--r--src/modules/navigator/offboard.cpp129
-rw-r--r--src/modules/navigator/offboard.h72
-rw-r--r--src/modules/navigator/rtl.cpp317
-rw-r--r--src/modules/navigator/rtl.h96
-rw-r--r--src/modules/navigator/rtl_params.c98
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c80
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c3
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h2
-rw-r--r--src/modules/px4iofirmware/controls.c4
-rw-r--r--src/modules/px4iofirmware/i2c.c5
-rw-r--r--src/modules/px4iofirmware/protocol.h2
-rw-r--r--src/modules/px4iofirmware/px4io.c5
-rw-r--r--src/modules/px4iofirmware/px4io.h4
-rw-r--r--src/modules/px4iofirmware/registers.c5
-rw-r--r--src/modules/px4iofirmware/sbus.c10
-rw-r--r--src/modules/sdlog2/sdlog2.c163
-rw-r--r--src/modules/sdlog2/sdlog2_format.h8
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h97
-rw-r--r--src/modules/sensors/sensor_params.c69
-rw-r--r--src/modules/sensors/sensors.cpp89
-rw-r--r--src/modules/systemlib/board_serial.c8
-rw-r--r--src/modules/systemlib/board_serial.h2
-rw-r--r--src/modules/systemlib/circuit_breaker.c93
-rw-r--r--src/modules/systemlib/circuit_breaker.h64
-rw-r--r--src/modules/systemlib/cpuload.c2
-rw-r--r--src/modules/systemlib/err.c2
-rw-r--r--src/modules/systemlib/hx_stream.c2
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp4
-rw-r--r--src/modules/systemlib/module.mk5
-rw-r--r--src/modules/systemlib/otp.c2
-rw-r--r--src/modules/systemlib/otp.h2
-rw-r--r--src/modules/systemlib/param/param.c2
-rw-r--r--src/modules/systemlib/perf_counter.c4
-rw-r--r--src/modules/systemlib/perf_counter.h2
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c1
-rw-r--r--src/modules/systemlib/rc_check.c13
-rw-r--r--src/modules/systemlib/state_table.h27
-rw-r--r--src/modules/systemlib/systemlib.c6
-rw-r--r--src/modules/uORB/Publication.cpp2
-rw-r--r--src/modules/uORB/Subscription.cpp2
-rw-r--r--src/modules/uORB/objects_common.cpp17
-rw-r--r--src/modules/uORB/topics/differential_pressure.h1
-rw-r--r--src/modules/uORB/topics/estimator_status.h6
-rw-r--r--src/modules/uORB/topics/home_position.h5
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h1
-rw-r--r--src/modules/uORB/topics/mission.h23
-rw-r--r--src/modules/uORB/topics/mission_result.h7
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h2
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h31
-rw-r--r--src/modules/uORB/topics/rc_channels.h68
-rw-r--r--src/modules/uORB/topics/satellite_info.h89
-rw-r--r--src/modules/uORB/topics/tecs_status.h93
-rw-r--r--src/modules/uORB/topics/telemetry_status.h25
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h2
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_force_setpoint.h65
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h13
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h14
-rw-r--r--src/modules/uORB/topics/vehicle_status.h62
-rw-r--r--src/modules/uORB/topics/wind_estimate.h (renamed from src/modules/mavlink/util.h)39
141 files changed, 13843 insertions, 5621 deletions
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 66a949af1..35dc39ec6 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -65,6 +65,7 @@
#include <drivers/drv_hrt.h>
#include <lib/mathlib/mathlib.h>
+#include <lib/geo/geo.h>
#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
@@ -287,6 +288,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
+ /* magnetic declination, in radians */
+ float mag_decl = 0.0f;
+
/* rotation matrix for magnetic declination */
math::Matrix<3, 3> R_decl;
R_decl.identity();
@@ -325,9 +329,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update parameters */
parameters_update(&ekf_param_handles, &ekf_params);
-
- /* update mag declination rotation matrix */
- R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
}
/* only run filter if sensor values changed */
@@ -340,6 +341,13 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_check(sub_gps, &gps_updated);
if (gps_updated) {
orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps);
+
+ if (gps.eph < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
+ mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
+
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, mag_decl);
+ }
}
bool global_pos_updated;
@@ -393,7 +401,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
hrt_abstime vel_t = 0;
bool vel_valid = false;
- if (ekf_params.acc_comp == 1 && gps.fix_type >= 3 && gps.eph_m < 10.0f && gps.vel_ned_valid && hrt_absolute_time() < gps.timestamp_velocity + 500000) {
+ if (ekf_params.acc_comp == 1 && gps.fix_type >= 3 && gps.eph < 10.0f && gps.vel_ned_valid && hrt_absolute_time() < gps.timestamp_velocity + 500000) {
vel_valid = true;
if (gps_updated) {
vel_t = gps.timestamp_velocity;
@@ -402,7 +410,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
vel(2) = gps.vel_d_m_s;
}
- } else if (ekf_params.acc_comp == 2 && gps.eph_m < 5.0f && global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
+ } else if (ekf_params.acc_comp == 2 && gps.eph < 5.0f && global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
vel_valid = true;
if (global_pos_updated) {
vel_t = global_pos.timestamp;
@@ -469,7 +477,15 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
parameters_update(&ekf_param_handles, &ekf_params);
/* update mag declination rotation matrix */
- R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl);
+ if (gps.eph < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) {
+ mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f));
+
+ } else {
+ mag_decl = ekf_params.mag_decl;
+ }
+
+ /* update mag declination rotation matrix */
+ R_decl.from_euler(0.0f, 0.0f, mag_decl);
x_aposteriori_k[0] = z_k[0];
x_aposteriori_k[1] = z_k[1];
@@ -515,7 +531,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
att.roll = euler[0];
att.pitch = euler[1];
- att.yaw = euler[2] + ekf_params.mag_decl;
+ att.yaw = euler[2] + mag_decl;
att.rollspeed = x_aposteriori[0];
att.pitchspeed = x_aposteriori[1];
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
index 3ff3d9922..bc0e3b93a 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.c
@@ -61,11 +61,6 @@ PARAM_DEFINE_FLOAT(EKF_ATT_V4_R2, 100.0f);
/* offset estimation - UNUSED */
PARAM_DEFINE_FLOAT(EKF_ATT_V4_R3, 0.0f);
-/* offsets in roll, pitch and yaw of sensor plane and body */
-PARAM_DEFINE_FLOAT(ATT_ROLL_OFF3, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_PITCH_OFF3, 0.0f);
-PARAM_DEFINE_FLOAT(ATT_YAW_OFF3, 0.0f);
-
/* magnetic declination, in degrees */
PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f);
@@ -85,10 +80,6 @@ int parameters_init(struct attitude_estimator_ekf_param_handles *h)
h->r2 = param_find("EKF_ATT_V4_R2");
h->r3 = param_find("EKF_ATT_V4_R3");
- h->roll_off = param_find("ATT_ROLL_OFF3");
- h->pitch_off = param_find("ATT_PITCH_OFF3");
- h->yaw_off = param_find("ATT_YAW_OFF3");
-
h->mag_decl = param_find("ATT_MAG_DECL");
h->acc_comp = param_find("ATT_ACC_COMP");
@@ -109,12 +100,8 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
param_get(h->r2, &(p->r[2]));
param_get(h->r3, &(p->r[3]));
- param_get(h->roll_off, &(p->roll_off));
- param_get(h->pitch_off, &(p->pitch_off));
- param_get(h->yaw_off, &(p->yaw_off));
-
param_get(h->mag_decl, &(p->mag_decl));
- p->mag_decl *= M_PI / 180.0f;
+ p->mag_decl *= M_PI_F / 180.0f;
param_get(h->acc_comp, &(p->acc_comp));
diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
index 74a141609..5985541ca 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_params.h
@@ -54,7 +54,6 @@ struct attitude_estimator_ekf_params {
struct attitude_estimator_ekf_param_handles {
param_t r0, r1, r2, r3;
param_t q0, q1, q2, q3, q4;
- param_t roll_off, pitch_off, yaw_off;
param_t mag_decl;
param_t acc_comp;
};
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 e55b01160..e49027e47 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -392,8 +392,6 @@ void NonlinearSO3AHRSupdate(float gx, float gy, float gz, float ax, float ay, fl
*/
int attitude_estimator_so3_thread_main(int argc, char *argv[])
{
- const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
-
//! Time constant
float dt = 0.005f;
@@ -438,11 +436,9 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
- int printcounter = 0;
thread_running = true;
- float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
// XXX write this out to perf regs
/* keep track of sensor updates */
@@ -513,7 +509,7 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
gyro_offsets[0] /= offset_count;
gyro_offsets[1] /= offset_count;
gyro_offsets[2] /= offset_count;
- warnx("gyro initialized, offsets: %.5f %.5f %.5f", gyro_offsets[0], gyro_offsets[1], gyro_offsets[2]);
+ warnx("gyro initialized, offsets: %.5f %.5f %.5f", (double)gyro_offsets[0], (double)gyro_offsets[1], (double)gyro_offsets[2]);
}
} else {
@@ -523,12 +519,9 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
/* Calculate data time difference in seconds */
dt = (raw.timestamp - last_measurement) / 1000000.0f;
last_measurement = raw.timestamp;
- uint8_t update_vect[3] = {0, 0, 0};
/* Fill in gyro measurements */
if (sensor_last_timestamp[0] != raw.timestamp) {
- update_vect[0] = 1;
- sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -538,8 +531,6 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
/* update accelerometer measurements */
if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
- update_vect[1] = 1;
- sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
@@ -549,8 +540,6 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
/* update magnetometer measurements */
if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
- update_vect[2] = 1;
- sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
@@ -569,8 +558,6 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
continue;
}
- uint64_t timing_start = hrt_absolute_time();
-
// NOTE : Accelerometer is reversed.
// Because proper mount of PX4 will give you a reversed accelerometer readings.
NonlinearSO3AHRSupdate(gyro[0], gyro[1], gyro[2],
@@ -609,9 +596,9 @@ int attitude_estimator_so3_thread_main(int argc, char *argv[])
/* due to inputs or numerical failure the output is invalid, skip it */
// Due to inputs or numerical failure the output is invalid
warnx("infinite euler angles, rotation matrix:");
- warnx("%.3f %.3f %.3f", Rot_matrix[0], Rot_matrix[1], Rot_matrix[2]);
- warnx("%.3f %.3f %.3f", Rot_matrix[3], Rot_matrix[4], Rot_matrix[5]);
- warnx("%.3f %.3f %.3f", Rot_matrix[6], Rot_matrix[7], Rot_matrix[8]);
+ warnx("%.3f %.3f %.3f", (double)Rot_matrix[0], (double)Rot_matrix[1], (double)Rot_matrix[2]);
+ warnx("%.3f %.3f %.3f", (double)Rot_matrix[3], (double)Rot_matrix[4], (double)Rot_matrix[5]);
+ warnx("%.3f %.3f %.3f", (double)Rot_matrix[6], (double)Rot_matrix[7], (double)Rot_matrix[8]);
// Don't publish anything
continue;
}
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 7180048ff..7a4e7a766 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -131,6 +130,7 @@
#include <fcntl.h>
#include <sys/prctl.h>
#include <math.h>
+#include <float.h>
#include <mathlib/mathlib.h>
#include <string.h>
#include <drivers/drv_hrt.h>
@@ -158,6 +158,8 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
int do_accel_calibration(int mavlink_fd)
{
+ int fd;
+
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
struct accel_scale accel_scale = {
@@ -172,7 +174,7 @@ int do_accel_calibration(int mavlink_fd)
int res = OK;
/* reset all offsets to zero and all scales to one */
- int fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, 0);
res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
close(fd);
@@ -223,7 +225,7 @@ int do_accel_calibration(int mavlink_fd)
if (res == OK) {
/* apply new scaling and offsets */
- int fd = open(ACCEL_DEVICE_PATH, 0);
+ fd = open(ACCEL_DEVICE_PATH, 0);
res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale);
close(fd);
@@ -524,7 +526,7 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0f) {
+ if (fabsf(det) < FLT_EPSILON) {
return ERROR; // Singular matrix
}
diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h
index 1cf9c0977..6b7e16d44 100644
--- a/src/modules/commander/accelerometer_calibration.h
+++ b/src/modules/commander/accelerometer_calibration.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index 5d21d89d0..0e58c68b6 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -51,6 +51,7 @@
#include <mavlink/mavlink_log.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
+#include <systemlib/airspeed.h>
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
@@ -64,19 +65,17 @@ int do_airspeed_calibration(int mavlink_fd)
{
/* give directions */
mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
- mavlink_log_info(mavlink_fd, "ensure airspeed sensor is not registering wind");
- const int calibration_count = 2000;
+ const unsigned calibration_count = 2000;
int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
struct differential_pressure_s diff_pres;
- int calibration_counter = 0;
float diff_pres_offset = 0.0f;
/* Reset sensor parameters */
struct airspeed_scale airscale = {
- 0.0f,
+ diff_pres_offset,
1.0f,
};
@@ -95,12 +94,29 @@ int do_airspeed_calibration(int mavlink_fd)
}
if (!paramreset_successful) {
- warn("FAILED to set scale / offsets for airspeed");
- mavlink_log_critical(mavlink_fd, "dpress reset failed");
- mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
- return ERROR;
+
+ /* only warn if analog scaling is zero */
+ float analog_scaling = 0.0f;
+ param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling));
+ if (fabsf(analog_scaling) < 0.1f) {
+ mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]");
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ /* set scaling offset parameter */
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
}
+ unsigned calibration_counter = 0;
+
+ mavlink_log_critical(mavlink_fd, "Ensure sensor is not measuring wind");
+ usleep(500 * 1000);
+
while (calibration_counter < calibration_count) {
/* wait blocking for new data */
@@ -112,11 +128,12 @@ int do_airspeed_calibration(int mavlink_fd)
if (poll_ret) {
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+
diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
if (calibration_counter % (calibration_count / 20) == 0) {
- mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 80) / calibration_count);
}
} else if (poll_ret == 0) {
@@ -131,6 +148,16 @@ int do_airspeed_calibration(int mavlink_fd)
if (isfinite(diff_pres_offset)) {
+ int fd_scale = open(AIRSPEED_DEVICE_PATH, 0);
+ airscale.offset_pa = diff_pres_offset;
+ if (fd_scale > 0) {
+ if (OK != ioctl(fd_scale, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
+ mavlink_log_critical(mavlink_fd, "airspeed offset update failed");
+ }
+
+ close(fd_scale);
+ }
+
if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
close(diff_pres_sub);
@@ -147,14 +174,91 @@ int do_airspeed_calibration(int mavlink_fd)
return ERROR;
}
- mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- tune_neutral(true);
- close(diff_pres_sub);
- return OK;
-
} else {
mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
close(diff_pres_sub);
return ERROR;
}
+
+ mavlink_log_critical(mavlink_fd, "Offset of %d Pa, create airflow now!", (int)diff_pres_offset);
+
+ /* wait 500 ms to ensure parameter propagated through the system */
+ usleep(500 * 1000);
+
+ calibration_counter = 0;
+ const unsigned maxcount = 3000;
+
+ /* just take a few samples and make sure pitot tubes are not reversed, timeout after ~30 seconds */
+ while (calibration_counter < maxcount) {
+
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = diff_pres_sub;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret) {
+ orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
+
+ calibration_counter++;
+
+ if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) {
+ if (calibration_counter % 100 == 0) {
+ mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ }
+ continue;
+ }
+
+ /* do not allow negative values */
+ if (diff_pres.differential_pressure_raw_pa < 0.0f) {
+ mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa);
+ close(diff_pres_sub);
+
+ /* the user setup is wrong, wipe the calibration to force a proper re-calibration */
+
+ diff_pres_offset = 0.0f;
+ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ /* save */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 0);
+ (void)param_save_default();
+
+ close(diff_pres_sub);
+
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ return ERROR;
+ } else {
+ mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)",
+ (int)diff_pres.differential_pressure_raw_pa);
+ break;
+ }
+
+ } else if (poll_ret == 0) {
+ /* any poll failure for 1s is a reason to abort */
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+ }
+
+ if (calibration_counter == maxcount) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ close(diff_pres_sub);
+ return ERROR;
+ }
+
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 100);
+
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
+ tune_neutral(true);
+ close(diff_pres_sub);
+ return OK;
}
diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h
index 71c701fc2..8c6b65ff1 100644
--- a/src/modules/commander/airspeed_calibration.h
+++ b/src/modules/commander/airspeed_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/baro_calibration.cpp b/src/modules/commander/baro_calibration.cpp
index 3123c4087..da98644b4 100644
--- a/src/modules/commander/baro_calibration.cpp
+++ b/src/modules/commander/baro_calibration.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/baro_calibration.h b/src/modules/commander/baro_calibration.h
index bc42bc6cf..ce78ae700 100644
--- a/src/modules/commander/baro_calibration.h
+++ b/src/modules/commander/baro_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h
index fd8b8564d..b1e209efc 100644
--- a/src/modules/commander/calibration_messages.h
+++ b/src/modules/commander/calibration_messages.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp
index be38ea104..5796204bf 100644
--- a/src/modules/commander/calibration_routines.cpp
+++ b/src/modules/commander/calibration_routines.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -40,6 +39,7 @@
*/
#include <math.h>
+#include <float.h>
#include "calibration_routines.h"
@@ -170,7 +170,7 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
float aA, aB, aC, nA, nB, nC, dA, dB, dC;
//Iterate N times, ignore stop condition.
- int n = 0;
+ unsigned int n = 0;
while (n < max_iterations) {
n++;
@@ -179,9 +179,9 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
aA = Q2 + 16.0f * (A2 - 2.0f * A * x_sum + x_sum2);
aB = Q2 + 16.0f * (B2 - 2.0f * B * y_sum + y_sum2);
aC = Q2 + 16.0f * (C2 - 2.0f * C * z_sum + z_sum2);
- aA = (aA == 0.0f) ? 1.0f : aA;
- aB = (aB == 0.0f) ? 1.0f : aB;
- aC = (aC == 0.0f) ? 1.0f : aC;
+ aA = (fabsf(aA) < FLT_EPSILON) ? 1.0f : aA;
+ aB = (fabsf(aB) < FLT_EPSILON) ? 1.0f : aB;
+ aC = (fabsf(aC) < FLT_EPSILON) ? 1.0f : aC;
//Compute next iteration
nA = A - ((F2 + 16.0f * (B * XY + C * XZ + x_sum * (-A2 - Q0) + A * (x_sum2 + Q1 - C * z_sum - B * y_sum))) / aA);
diff --git a/src/modules/commander/calibration_routines.h b/src/modules/commander/calibration_routines.h
index e3e7fbafd..3c8e49ee9 100644
--- a/src/modules/commander/calibration_routines.h
+++ b/src/modules/commander/calibration_routines.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 65922b2a5..0c4d48dea 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -1,11 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Anton Babushkin <anton.babushkin@me.com>
+ * 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
@@ -38,8 +33,13 @@
/**
* @file commander.cpp
- * Main system state machine implementation.
+ * Main fail-safe handling.
*
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
@@ -52,6 +52,7 @@
#include <fcntl.h>
#include <errno.h>
#include <systemlib/err.h>
+#include <systemlib/circuit_breaker.h>
#include <debug.h>
#include <sys/prctl.h>
#include <sys/stat.h>
@@ -76,6 +77,10 @@
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/differential_pressure.h>
#include <uORB/topics/safety.h>
+#include <uORB/topics/system_power.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+#include <uORB/topics/telemetry_status.h>
#include <drivers/drv_led.h>
#include <drivers/drv_hrt.h>
@@ -87,6 +92,8 @@
#include <systemlib/err.h>
#include <systemlib/cpuload.h>
#include <systemlib/rc_check.h>
+#include <systemlib/state_table.h>
+#include <dataman/dataman.h>
#include "px4_custom_mode.h"
#include "commander_helper.h"
@@ -120,6 +127,8 @@ extern struct system_load_s system_load;
#define POSITION_TIMEOUT (600 * 1000) /**< consider the local or global position estimate invalid after 600ms */
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
#define RC_TIMEOUT 500000
+#define DL_TIMEOUT 5 * 1000* 1000
+#define OFFBOARD_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
@@ -160,6 +169,7 @@ static struct vehicle_status_s status;
static struct actuator_armed_s armed;
static struct safety_s safety;
static struct vehicle_control_mode_s control_mode;
+static struct offboard_control_setpoint_s sp_offboard;
/* tasks waiting for low prio thread */
typedef enum {
@@ -278,15 +288,22 @@ int commander_main(int argc, char *argv[])
exit(0);
}
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("\tcommander is running");
- print_status();
+ /* commands needing the app to run below */
+ if (!thread_running) {
+ warnx("\tcommander not started");
+ exit(1);
+ }
- } else {
- warnx("\tcommander not started");
- }
+ if (!strcmp(argv[1], "status")) {
+ print_status();
+ exit(0);
+ }
+ if (!strcmp(argv[1], "check")) {
+ int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0);
+ int checkres = prearm_check(&status, mavlink_fd_local);
+ close(mavlink_fd_local);
+ warnx("FINAL RESULT: %s", (checkres == 0) ? "OK" : "FAILED");
exit(0);
}
@@ -295,7 +312,7 @@ int commander_main(int argc, char *argv[])
exit(0);
}
- if (!strcmp(argv[1], "2")) {
+ if (!strcmp(argv[1], "disarm")) {
arm_disarm(false, mavlink_fd, "command line");
exit(0);
}
@@ -316,6 +333,7 @@ void usage(const char *reason)
void print_status()
{
+ warnx("type: %s", (status.is_rotary_wing) ? "ROTARY" : "PLANE");
warnx("usb powered: %s", (on_usb_power) ? "yes" : "no");
/* read all relevant states */
@@ -367,16 +385,16 @@ void print_status()
static orb_advert_t status_pub;
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy)
+transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char *armedBy)
{
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
// Transition the armed state. By passing mavlink_fd to arming_state_transition it will
// output appropriate error messages if the state cannot transition.
- arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd_local);
if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
- mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
+ mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
} else if (arming_res == TRANSITION_DENIED) {
tune_negative(true);
@@ -385,133 +403,113 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armed
return arming_res;
}
-bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
+bool handle_command(struct vehicle_status_s *status_local, const struct safety_s *safety_local,
+ struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local,
+ struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
{
- /* result of the command */
- enum VEHICLE_CMD_RESULT result = VEHICLE_CMD_RESULT_UNSUPPORTED;
- bool ret = false;
-
/* only handle commands that are meant to be handled by this system and component */
- if (cmd->target_system != status->system_id || ((cmd->target_component != status->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
+ if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components
return false;
}
- /* only handle high-priority commands here */
+ /* result of the command */
+ enum VEHICLE_CMD_RESULT cmd_result = VEHICLE_CMD_RESULT_UNSUPPORTED;
/* request to set different system mode */
switch (cmd->command) {
case VEHICLE_CMD_DO_SET_MODE: {
- uint8_t base_mode = (uint8_t) cmd->param1;
- uint8_t custom_main_mode = (uint8_t) cmd->param2;
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- /* set HIL state */
- hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
- int hil_ret = hil_state_transition(new_hil_state, status_pub, status, mavlink_fd);
+ uint8_t base_mode = (uint8_t)cmd->param1;
+ uint8_t custom_main_mode = (uint8_t)cmd->param2;
- /* if HIL got enabled, reset battery status state */
- if (hil_ret == OK && status->hil_state == HIL_STATE_ON) {
- /* reset the arming mode to disarmed */
- arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed);
+ transition_result_t arming_ret = TRANSITION_NOT_CHANGED;
- if (arming_res != TRANSITION_DENIED) {
- mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby");
-
- } else {
- mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state");
- }
- }
+ transition_result_t main_ret = TRANSITION_NOT_CHANGED;
- if (hil_ret == OK) {
- ret = true;
- }
+ /* set HIL state */
+ hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF;
+ transition_result_t hil_ret = hil_state_transition(new_hil_state, status_pub, status_local, mavlink_fd);
// Transition the arming state
- arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
-
- if (arming_res == TRANSITION_CHANGED) {
- ret = true;
- }
-
- /* set main state */
- transition_result_t main_res = TRANSITION_DENIED;
+ arming_ret = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
/* use autopilot-specific mode */
if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
/* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
/* ALTCTL */
- main_res = main_state_transition(status, MAIN_STATE_ALTCTL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_ALTCTL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
/* POSCTL */
- main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
/* ACRO */
- main_res = main_state_transition(status, MAIN_STATE_ACRO);
+ main_ret = main_state_transition(status_local, MAIN_STATE_ACRO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
+ /* OFFBOARD */
+ main_ret = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
}
} else {
/* use base mode */
if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) {
/* AUTO */
- main_res = main_state_transition(status, MAIN_STATE_AUTO);
+ main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
/* POSCTL */
- main_res = main_state_transition(status, MAIN_STATE_POSCTL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL);
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
/* MANUAL */
- main_res = main_state_transition(status, MAIN_STATE_MANUAL);
+ main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL);
}
}
}
- if (main_res == TRANSITION_CHANGED) {
- ret = true;
- }
-
- if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ if (hil_ret != TRANSITION_DENIED && arming_ret != TRANSITION_DENIED && main_ret != TRANSITION_DENIED) {
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
-
- break;
}
+ break;
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
- // We use an float epsilon delta to test float equality.
- if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
- mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
+ // Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints
+ // for logic state parameters
+
+ if (static_cast<int>(cmd->param1 + 0.5f) != 0 && static_cast<int>(cmd->param1 + 0.5f) != 1) {
+ mavlink_log_critical(mavlink_fd, "Unsupported ARM_DISARM param: %.3f", (double)cmd->param1);
} else {
+ bool cmd_arms = (static_cast<int>(cmd->param1 + 0.5f) == 1);
+
// Flick to inair restore first if this comes from an onboard system
- if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
- status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
+ if (cmd->source_system == status_local->system_id && cmd->source_component == status_local->component_id) {
+ status_local->arming_state = ARMING_STATE_IN_AIR_RESTORE;
}
- transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
+ transition_result_t arming_res = arm_disarm(cmd_arms, mavlink_fd, "arm/disarm component command");
if (arming_res == TRANSITION_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ mavlink_log_critical(mavlink_fd, "REJECTING component arm cmd");
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
} else {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
}
}
}
@@ -519,62 +517,70 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
case VEHICLE_CMD_OVERRIDE_GOTO: {
// TODO listen vehicle_command topic directly from navigator (?)
- unsigned int mav_goto = cmd->param1;
+
+ // Increase by 0.5f and rely on the integer cast
+ // implicit floor(). This is the *safest* way to
+ // convert from floats representing small ints to actual ints.
+ unsigned int mav_goto = (cmd->param1 + 0.5f);
if (mav_goto == 0) { // MAV_GOTO_DO_HOLD
- status->set_nav_state = NAV_STATE_LOITER;
- status->set_nav_state_timestamp = hrt_absolute_time();
- mavlink_log_critical(mavlink_fd, "#audio: pause mission cmd");
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- ret = true;
+ status_local->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ mavlink_log_critical(mavlink_fd, "Pause mission cmd");
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE
- status->set_nav_state = NAV_STATE_MISSION;
- status->set_nav_state_timestamp = hrt_absolute_time();
- mavlink_log_critical(mavlink_fd, "#audio: continue mission cmd");
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- ret = true;
+ status_local->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ mavlink_log_critical(mavlink_fd, "Continue mission cmd");
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- mavlink_log_info(mavlink_fd, "Unsupported OVERRIDE_GOTO: %f %f %f %f %f %f %f %f", cmd->param1, cmd->param2, cmd->param3, cmd->param4, cmd->param5, cmd->param6, cmd->param7);
+ mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f",
+ (double)cmd->param1,
+ (double)cmd->param2,
+ (double)cmd->param3,
+ (double)cmd->param4,
+ (double)cmd->param5,
+ (double)cmd->param6,
+ (double)cmd->param7);
}
}
break;
+#if 0
/* Flight termination */
case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
//XXX: to enable the parachute, a param needs to be set
//xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO
- if (armed->armed && cmd->param3 > 0.5 && parachute_enabled) {
+ if (armed_local->armed && cmd->param3 > 0.5 && parachute_enabled) {
transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION);
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- ret = true;
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
/* reject parachute depoyment not armed */
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
}
break;
+#endif
case VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
if (use_current) {
/* use current position */
- if (status->condition_global_position_valid) {
+ if (status_local->condition_global_position_valid) {
home->lat = global_pos->lat;
home->lon = global_pos->lon;
home->alt = global_pos->alt;
home->timestamp = hrt_absolute_time();
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
} else {
@@ -585,10 +591,10 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
home->timestamp = hrt_absolute_time();
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
}
- if (result == VEHICLE_CMD_RESULT_ACCEPTED) {
+ if (cmd_result == VEHICLE_CMD_RESULT_ACCEPTED) {
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home->lat, home->lon, (double)home->alt);
mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home->lat, home->lon, (double)home->alt);
@@ -601,7 +607,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
/* mark home position as set */
- status->condition_home_position_valid = true;
+ status_local->condition_home_position_valid = true;
}
}
break;
@@ -620,17 +626,18 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
break;
}
- if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ if (cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
- answer_command(*cmd, result);
+ answer_command(*cmd, cmd_result);
}
/* send any requested ACKs */
- if (cmd->confirmation > 0 && result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
+ if (cmd->confirmation > 0 && cmd_result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* send acknowledge command */
// XXX TODO
}
+ return true;
}
int commander_thread_main(int argc, char *argv[])
@@ -647,42 +654,54 @@ int commander_thread_main(int argc, char *argv[])
param_t _param_component_id = param_find("MAV_COMP_ID");
param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT");
param_t _param_enable_parachute = param_find("NAV_PARACHUTE_EN");
+ param_t _param_enable_datalink_loss = param_find("COM_DL_LOSS_EN");
/* welcome user */
warnx("starting");
- char *main_states_str[MAIN_STATE_MAX];
- main_states_str[0] = "MANUAL";
- main_states_str[1] = "ALTCTL";
- main_states_str[2] = "POSCTL";
- main_states_str[3] = "AUTO";
- main_states_str[4] = "ACRO";
-
- char *arming_states_str[ARMING_STATE_MAX];
- arming_states_str[0] = "INIT";
- arming_states_str[1] = "STANDBY";
- arming_states_str[2] = "ARMED";
- arming_states_str[3] = "ARMED_ERROR";
- arming_states_str[4] = "STANDBY_ERROR";
- arming_states_str[5] = "REBOOT";
- arming_states_str[6] = "IN_AIR_RESTORE";
-
- char *failsafe_states_str[FAILSAFE_STATE_MAX];
- failsafe_states_str[0] = "NORMAL";
- failsafe_states_str[1] = "RTL";
- failsafe_states_str[2] = "LAND";
- failsafe_states_str[3] = "TERMINATION";
+ const char *main_states_str[MAIN_STATE_MAX];
+ main_states_str[MAIN_STATE_MANUAL] = "MANUAL";
+ main_states_str[MAIN_STATE_ALTCTL] = "ALTCTL";
+ main_states_str[MAIN_STATE_POSCTL] = "POSCTL";
+ main_states_str[MAIN_STATE_AUTO_MISSION] = "AUTO_MISSION";
+ main_states_str[MAIN_STATE_AUTO_LOITER] = "AUTO_LOITER";
+ main_states_str[MAIN_STATE_AUTO_RTL] = "AUTO_RTL";
+ main_states_str[MAIN_STATE_ACRO] = "ACRO";
+ main_states_str[MAIN_STATE_OFFBOARD] = "OFFBOARD";
+
+ const char *arming_states_str[ARMING_STATE_MAX];
+ arming_states_str[ARMING_STATE_INIT] = "INIT";
+ arming_states_str[ARMING_STATE_STANDBY] = "STANDBY";
+ arming_states_str[ARMING_STATE_ARMED] = "ARMED";
+ arming_states_str[ARMING_STATE_ARMED_ERROR] = "ARMED_ERROR";
+ arming_states_str[ARMING_STATE_STANDBY_ERROR] = "STANDBY_ERROR";
+ arming_states_str[ARMING_STATE_REBOOT] = "REBOOT";
+ arming_states_str[ARMING_STATE_IN_AIR_RESTORE] = "IN_AIR_RESTORE";
+
+ const char *nav_states_str[NAVIGATION_STATE_MAX];
+ nav_states_str[NAVIGATION_STATE_MANUAL] = "MANUAL";
+ nav_states_str[NAVIGATION_STATE_ALTCTL] = "ALTCTL";
+ nav_states_str[NAVIGATION_STATE_POSCTL] = "POSCTL";
+ nav_states_str[NAVIGATION_STATE_AUTO_MISSION] = "AUTO_MISSION";
+ nav_states_str[NAVIGATION_STATE_AUTO_LOITER] = "AUTO_LOITER";
+ nav_states_str[NAVIGATION_STATE_AUTO_RTL] = "AUTO_RTL";
+ nav_states_str[NAVIGATION_STATE_AUTO_RTGS] = "AUTO_RTGS";
+ nav_states_str[NAVIGATION_STATE_ACRO] = "ACRO";
+ nav_states_str[NAVIGATION_STATE_LAND] = "LAND";
+ nav_states_str[NAVIGATION_STATE_DESCEND] = "DESCEND";
+ nav_states_str[NAVIGATION_STATE_TERMINATION] = "TERMINATION";
+ nav_states_str[NAVIGATION_STATE_OFFBOARD] = "OFFBOARD";
/* pthread for slow low prio thread */
pthread_t commander_low_prio_thread;
/* initialize */
if (led_init() != 0) {
- warnx("ERROR: Failed to initialize leds");
+ warnx("ERROR: LED INIT FAIL");
}
if (buzzer_init() != OK) {
- warnx("ERROR: Failed to initialize buzzer");
+ warnx("ERROR: BUZZER INIT FAIL");
}
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
@@ -693,11 +712,10 @@ int commander_thread_main(int argc, char *argv[])
// We want to accept RC inputs as default
status.rc_input_blocked = false;
status.main_state = MAIN_STATE_MANUAL;
- status.set_nav_state = NAV_STATE_NONE;
- status.set_nav_state_timestamp = 0;
+ status.nav_state = NAVIGATION_STATE_MANUAL;
status.arming_state = ARMING_STATE_INIT;
status.hil_state = HIL_STATE_OFF;
- status.failsafe_state = FAILSAFE_STATE_NORMAL;
+ status.failsafe = false;
/* neither manual nor offboard control commands have been received */
status.offboard_control_signal_found_once = false;
@@ -706,6 +724,7 @@ int commander_thread_main(int argc, char *argv[])
/* mark all signals lost as long as they haven't been found */
status.rc_signal_lost = true;
status.offboard_control_signal_lost = true;
+ status.data_link_lost = true;
/* set battery warning flag */
status.battery_warning = VEHICLE_BATTERY_WARNING_NONE;
@@ -717,8 +736,19 @@ int commander_thread_main(int argc, char *argv[])
status.counter++;
status.timestamp = hrt_absolute_time();
+ status.condition_power_input_valid = true;
+ status.avionics_power_rail_voltage = -1.0f;
+
+ // CIRCUIT BREAKERS
+ status.circuit_breaker_engaged_power_check = false;
+
/* publish initial state */
status_pub = orb_advertise(ORB_ID(vehicle_status), &status);
+ if (status_pub < 0) {
+ warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
+ warnx("exiting.");
+ exit(ERROR);
+ }
/* armed topic */
orb_advert_t armed_pub;
@@ -736,13 +766,29 @@ int commander_thread_main(int argc, char *argv[])
struct home_position_s home;
memset(&home, 0, sizeof(home));
- if (status_pub < 0) {
- warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n");
- warnx("exiting.");
- exit(ERROR);
- }
+ /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */
+ orb_advert_t mission_pub = -1;
+ mission_s mission;
+ if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) {
+ if (mission.dataman_id >= 0 && mission.dataman_id <= 1) {
+ warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq);
+ mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d",
+ mission.dataman_id, mission.count, mission.current_seq);
+ } else {
+ const char *missionfail = "reading mission state failed";
+ warnx("%s", missionfail);
+ mavlink_log_critical(mavlink_fd, missionfail);
+
+ /* initialize mission state in dataman */
+ mission.dataman_id = 0;
+ mission.count = 0;
+ mission.current_seq = 0;
+ dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s));
+ }
- mavlink_log_info(mavlink_fd, "[cmd] started");
+ mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
+ orb_publish(ORB_ID(offboard_mission), mission_pub, &mission);
+ }
int ret;
@@ -769,14 +815,13 @@ int commander_thread_main(int argc, char *argv[])
hrt_abstime last_idle_time = 0;
hrt_abstime start_time = 0;
- hrt_abstime last_auto_state_valid = 0;
bool status_changed = true;
bool param_init_forced = true;
bool updated = false;
- bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+ rc_calibration_check(mavlink_fd);
/* Subscribe to safety topic */
int safety_sub = orb_subscribe(ORB_ID(safety));
@@ -784,6 +829,11 @@ int commander_thread_main(int argc, char *argv[])
safety.safety_switch_available = false;
safety.safety_off = false;
+ /* Subscribe to mission result topic */
+ int mission_result_sub = orb_subscribe(ORB_ID(mission_result));
+ struct mission_result_s mission_result;
+ memset(&mission_result, 0, sizeof(mission_result));
+
/* Subscribe to manual control data */
int sp_man_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
struct manual_control_setpoint_s sp_man;
@@ -791,9 +841,19 @@ int commander_thread_main(int argc, char *argv[])
/* Subscribe to offboard control data */
int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- struct offboard_control_setpoint_s sp_offboard;
memset(&sp_offboard, 0, sizeof(sp_offboard));
+ /* Subscribe to telemetry status topics */
+ int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
+ uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM];
+ bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM];
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ telemetry_last_heartbeat[i] = 0;
+ telemetry_lost[i] = true;
+ }
+
/* Subscribe to global position */
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
struct vehicle_global_position_s global_position;
@@ -853,6 +913,11 @@ int commander_thread_main(int argc, char *argv[])
struct position_setpoint_triplet_s pos_sp_triplet;
memset(&pos_sp_triplet, 0, sizeof(pos_sp_triplet));
+ /* Subscribe to system power */
+ int system_power_sub = orb_subscribe(ORB_ID(system_power));
+ struct system_power_s system_power;
+ memset(&system_power, 0, sizeof(system_power));
+
control_status_leds(&status, &armed, true);
/* now initialized */
@@ -861,6 +926,15 @@ int commander_thread_main(int argc, char *argv[])
start_time = hrt_absolute_time();
+ transition_result_t arming_ret;
+
+ int32_t datalink_loss_enabled = false;
+
+ /* check which state machines for changes, clear "changed" flag */
+ bool arming_state_changed = false;
+ bool main_state_changed = false;
+ bool failsafe_old = false;
+
while (!thread_should_exit) {
if (mavlink_fd < 0 && counter % (1000000 / MAVLINK_OPEN_INTERVAL) == 0) {
@@ -868,6 +942,9 @@ int commander_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
+ arming_ret = TRANSITION_NOT_CHANGED;
+
+
/* update parameters */
orb_check(param_changed_sub, &updated);
@@ -898,15 +975,19 @@ int commander_thread_main(int argc, char *argv[])
/* check and update system / component ID */
param_get(_param_system_id, &(status.system_id));
param_get(_param_component_id, &(status.component_id));
+
+ status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY);
+
status_changed = true;
/* re-check RC calibration */
- rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+ rc_calibration_check(mavlink_fd);
}
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
param_get(_param_enable_parachute, &parachute_enabled);
+ param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
}
orb_check(sp_man_sub, &updated);
@@ -921,6 +1002,41 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
}
+ if (sp_offboard.timestamp != 0 &&
+ sp_offboard.timestamp + OFFBOARD_TIMEOUT > hrt_absolute_time()) {
+ if (status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = false;
+ status_changed = true;
+ }
+ } else {
+ if (!status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = true;
+ status_changed = true;
+ }
+ }
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ orb_check(telemetry_subs[i], &updated);
+
+ if (updated) {
+ struct telemetry_status_s telemetry;
+ memset(&telemetry, 0, sizeof(telemetry));
+
+ orb_copy(telemetry_status_orb_id[i], telemetry_subs[i], &telemetry);
+
+ /* perform system checks when new telemetry link connected */
+ if (mavlink_fd &&
+ telemetry_last_heartbeat[i] == 0 &&
+ telemetry.heartbeat_time > 0 &&
+ hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) {
+
+ (void)rc_calibration_check(mavlink_fd);
+ }
+
+ telemetry_last_heartbeat[i] = telemetry.heartbeat_time;
+ }
+ }
+
orb_check(sensor_sub, &updated);
if (updated) {
@@ -933,6 +1049,26 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres);
}
+ orb_check(system_power_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(system_power), system_power_sub, &system_power);
+
+ if (hrt_elapsed_time(&system_power.timestamp) < 200000) {
+ if (system_power.servo_valid &&
+ !system_power.brick_valid &&
+ !system_power.usb_connected) {
+ /* flying only on servo rail, this is unsafe */
+ status.condition_power_input_valid = false;
+ } else {
+ status.condition_power_input_valid = true;
+ }
+
+ /* copy avionics voltage */
+ status.avionics_power_rail_voltage = system_power.voltage5V_v;
+ }
+ }
+
check_valid(diff_pres.timestamp, DIFFPRESS_TIMEOUT, true, &(status.condition_airspeed_valid), &status_changed);
/* update safety topic */
@@ -945,8 +1081,9 @@ int commander_thread_main(int argc, char *argv[])
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) {
- mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch");
+ if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) {
+ mavlink_log_info(mavlink_fd, "DISARMED by safety switch");
+ arming_state_changed = true;
}
}
}
@@ -959,6 +1096,14 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_global_position), global_position_sub, &global_position);
}
+ /* update local position estimate */
+ orb_check(local_position_sub, &updated);
+
+ if (updated) {
+ /* position changed */
+ orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
+ }
+
/* update condition_global_position_valid */
/* hysteresis for EPH/EPV */
bool eph_epv_good;
@@ -992,6 +1137,10 @@ int commander_thread_main(int argc, char *argv[])
home.lon = global_position.lon;
home.alt = global_position.alt;
+ home.x = local_position.x;
+ home.y = local_position.y;
+ home.z = local_position.z;
+
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
@@ -1008,14 +1157,6 @@ int commander_thread_main(int argc, char *argv[])
tune_positive(true);
}
- /* update local position estimate */
- orb_check(local_position_sub, &updated);
-
- if (updated) {
- /* position changed */
- orb_copy(ORB_ID(vehicle_local_position), local_position_sub, &local_position);
- }
-
/* update condition_local_position_valid and condition_local_altitude_valid */
/* hysteresis for EPH */
bool local_eph_good;
@@ -1039,28 +1180,18 @@ int commander_thread_main(int argc, char *argv[])
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
- static bool published_condition_landed_fw = false;
-
- if (status.is_rotary_wing && status.condition_local_altitude_valid) {
+ if (status.condition_local_altitude_valid) {
if (status.condition_landed != local_position.landed) {
status.condition_landed = local_position.landed;
status_changed = true;
- published_condition_landed_fw = false; //make sure condition_landed is published again if the system type changes
if (status.condition_landed) {
- mavlink_log_critical(mavlink_fd, "#audio: LANDED");
+ mavlink_log_critical(mavlink_fd, "LANDED MODE");
} else {
- mavlink_log_critical(mavlink_fd, "#audio: IN AIR");
+ mavlink_log_critical(mavlink_fd, "IN AIR MODE");
}
}
-
- } else {
- if (!published_condition_landed_fw) {
- status.condition_landed = false; // Fixedwing does not have a landing detector currently
- published_condition_landed_fw = true;
- status_changed = true;
- }
}
/* update battery status */
@@ -1138,23 +1269,30 @@ int commander_thread_main(int argc, char *argv[])
/* if battery voltage is getting lower, warn using buzzer, etc. */
if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) {
low_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY");
+ mavlink_log_critical(mavlink_fd, "LOW BATTERY, RETURN TO LAND ADVISED");
status.battery_warning = VEHICLE_BATTERY_WARNING_LOW;
status_changed = true;
} else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) {
/* critical battery voltage, this is rather an emergency, change state machine */
critical_battery_voltage_actions_done = true;
- mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY");
+ mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY");
status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL;
if (armed.armed) {
- arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd);
+
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
} else {
- arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed);
- }
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
+ }
status_changed = true;
}
@@ -1162,11 +1300,15 @@ int commander_thread_main(int argc, char *argv[])
/* If in INIT state, try to proceed to STANDBY state */
if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) {
- // XXX check for sensors
- arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
+ /* TODO: check for sensors */
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
+
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
} else {
- // XXX: Add emergency stuff if sensors are lost
+ /* TODO: Add emergency stuff if sensors are lost */
}
@@ -1185,28 +1327,29 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_gps_position), gps_sub, &gps_position);
}
- /* start RC input check */
+ orb_check(mission_result_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
+ }
+
+ /* RC input check */
if (!status.rc_input_blocked && sp_man.timestamp != 0 && hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) {
/* handle the case where RC signal was regained */
if (!status.rc_signal_found_once) {
status.rc_signal_found_once = true;
- mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time");
+ mavlink_log_critical(mavlink_fd, "detected RC signal first time");
status_changed = true;
} else {
if (status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: RC signal regained");
+ mavlink_log_critical(mavlink_fd, "RC signal regained");
status_changed = true;
}
}
status.rc_signal_lost = false;
- transition_result_t arming_res; // store all transitions results here
-
- /* arm/disarm by RC */
- arming_res = TRANSITION_NOT_CHANGED;
-
/* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSIST mode and landed) -> disarm
* do it only for rotary wings */
if (status.is_rotary_wing &&
@@ -1217,7 +1360,10 @@ int commander_thread_main(int argc, char *argv[])
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed);
+ arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
stick_off_counter = 0;
} else {
@@ -1232,14 +1378,18 @@ int commander_thread_main(int argc, char *argv[])
if (status.arming_state == ARMING_STATE_STANDBY &&
sp_man.r > STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
- if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) {
- print_reject_arm("#audio: NOT ARMING: Press safety switch first.");
-
- } else if (status.main_state != MAIN_STATE_MANUAL) {
- print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
+ /* we check outside of the transition function here because the requirement
+ * for being in manual mode only applies to manual arming actions.
+ * the system can be armed in auto if armed via the GCS.
+ */
+ if (status.main_state != MAIN_STATE_MANUAL) {
+ print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
} else {
- arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd);
+ if (arming_ret == TRANSITION_CHANGED) {
+ arming_state_changed = true;
+ }
}
stick_on_counter = 0;
@@ -1252,22 +1402,19 @@ int commander_thread_main(int argc, char *argv[])
stick_on_counter = 0;
}
- if (arming_res == TRANSITION_CHANGED) {
+ if (arming_ret == TRANSITION_CHANGED) {
if (status.arming_state == ARMING_STATE_ARMED) {
- mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
+ mavlink_log_info(mavlink_fd, "ARMED by RC");
} else {
- mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
+ mavlink_log_info(mavlink_fd, "DISARMED by RC");
}
+ arming_state_changed = true;
- } else if (arming_res == TRANSITION_DENIED) {
+ } else if (arming_ret == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
- mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied");
- }
-
- if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
- /* recover from failsafe */
- (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ mavlink_log_critical(mavlink_fd, "arming state transition denied");
+ tune_negative(true);
}
/* evaluate the main state machine according to mode switches */
@@ -1276,100 +1423,52 @@ int commander_thread_main(int argc, char *argv[])
/* play tune on mode change only if armed, blink LED always */
if (main_res == TRANSITION_CHANGED) {
tune_positive(armed.armed);
+ main_state_changed = true;
} else if (main_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
- mavlink_log_critical(mavlink_fd, "ERROR: main state transition denied");
- }
-
- /* set navigation state */
- /* RETURN switch, overrides MISSION switch */
- if (sp_man.return_switch == SWITCH_POS_ON) {
- /* switch to RTL if not already landed after RTL and home position set */
- status.set_nav_state = NAV_STATE_RTL;
- status.set_nav_state_timestamp = hrt_absolute_time();
-
- } else {
-
- /* LOITER switch */
- if (sp_man.loiter_switch == SWITCH_POS_ON) {
- /* stick is in LOITER position */
- status.set_nav_state = NAV_STATE_LOITER;
- status.set_nav_state_timestamp = hrt_absolute_time();
-
- } else if (sp_man.loiter_switch != SWITCH_POS_NONE) {
- /* stick is in MISSION position */
- status.set_nav_state = NAV_STATE_MISSION;
- status.set_nav_state_timestamp = hrt_absolute_time();
-
- } else if ((sp_man.return_switch == SWITCH_POS_OFF || sp_man.return_switch == SWITCH_POS_MIDDLE) &&
- pos_sp_triplet.nav_state == NAV_STATE_RTL) {
- /* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */
- status.set_nav_state = NAV_STATE_MISSION;
- status.set_nav_state_timestamp = hrt_absolute_time();
- }
+ mavlink_log_critical(mavlink_fd, "main state transition denied");
}
} else {
if (!status.rc_signal_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST");
+ mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST");
status.rc_signal_lost = true;
status_changed = true;
}
+ }
- if (armed.armed) {
- if (status.main_state == MAIN_STATE_AUTO) {
- /* check if AUTO mode still allowed */
- transition_result_t auto_res = main_state_transition(&status, MAIN_STATE_AUTO);
-
- if (auto_res == TRANSITION_NOT_CHANGED) {
- last_auto_state_valid = hrt_absolute_time();
- }
-
- /* still invalid state after the timeout interval, execute failsafe */
- if ((hrt_elapsed_time(&last_auto_state_valid) > FAILSAFE_DEFAULT_TIMEOUT) && (auto_res == TRANSITION_DENIED)) {
- /* AUTO mode denied, don't try RTL, switch to failsafe state LAND */
- auto_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
-
- if (auto_res == TRANSITION_DENIED) {
- /* LAND not allowed, set TERMINATION state */
- (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
- }
- }
-
- } else {
- /* failsafe for manual modes */
- transition_result_t manual_res = TRANSITION_DENIED;
-
- if (!status.condition_landed) {
- /* vehicle is not landed, try to perform RTL */
- manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
- }
-
- if (manual_res == TRANSITION_DENIED) {
- /* RTL not allowed (no global position estimate) or not wanted, try LAND */
- manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
-
- if (manual_res == TRANSITION_DENIED) {
- /* LAND not allowed, set TERMINATION state */
- (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
- }
- }
+ /* data links check */
+ bool have_link = false;
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
+ /* handle the case where data link was regained */
+ if (telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "data link %i regained", i);
+ telemetry_lost[i] = false;
}
+ have_link = true;
} else {
- if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
- /* reset failsafe when disarmed */
- (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ if (!telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "data link %i lost", i);
+ telemetry_lost[i] = true;
}
}
}
- // TODO remove this hack
- /* flight termination in manual mode if assist switch is on POSCTL position */
- if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctl_switch == SWITCH_POS_ON) {
- if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
- tune_positive(armed.armed);
+ if (have_link) {
+ /* handle the case where data link was regained */
+ if (status.data_link_lost) {
+ status.data_link_lost = false;
+ status_changed = true;
+ }
+
+ } else {
+ if (!status.data_link_lost) {
+ mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST");
+ status.data_link_lost = true;
+ status_changed = true;
}
}
@@ -1386,11 +1485,6 @@ int commander_thread_main(int argc, char *argv[])
}
}
- /* check which state machines for changes, clear "changed" flag */
- bool arming_state_changed = check_arming_state_changed();
- bool main_state_changed = check_main_state_changed();
- bool failsafe_state_changed = check_failsafe_state_changed();
-
hrt_abstime t1 = hrt_absolute_time();
/* print new state */
@@ -1407,6 +1501,10 @@ int commander_thread_main(int argc, char *argv[])
home.lon = global_position.lon;
home.alt = global_position.alt;
+ home.x = local_position.x;
+ home.y = local_position.y;
+ home.z = local_position.z;
+
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
mavlink_log_info(mavlink_fd, "home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
@@ -1421,18 +1519,33 @@ int commander_thread_main(int argc, char *argv[])
/* mark home position as set */
status.condition_home_position_valid = true;
}
+ arming_state_changed = false;
}
was_armed = armed.armed;
+ /* now set navigation state according to failsafe and main state */
+ bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled,
+ mission_result.finished);
+
+ // TODO handle mode changes by commands
if (main_state_changed) {
status_changed = true;
+ warnx("main state: %s", main_states_str[status.main_state]);
mavlink_log_info(mavlink_fd, "[cmd] main state: %s", main_states_str[status.main_state]);
+ main_state_changed = false;
+ }
+
+ if (status.failsafe != failsafe_old) {
+ status_changed = true;
+ mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %i", status.failsafe);
+ failsafe_old = status.failsafe;
}
- if (failsafe_state_changed) {
+ if (nav_state_changed) {
status_changed = true;
- mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %s", failsafe_states_str[status.failsafe_state]);
+ warnx("nav state: %s", nav_states_str[status.nav_state]);
+ mavlink_log_info(mavlink_fd, "[cmd] nav state: %s", nav_states_str[status.nav_state]);
}
/* publish states (armed, control mode, vehicle status) at least with 5 Hz */
@@ -1458,7 +1571,7 @@ int commander_thread_main(int argc, char *argv[])
/* play tune on battery critical */
set_tune(TONE_BATTERY_WARNING_FAST_TUNE);
- } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe_state != FAILSAFE_STATE_NORMAL) {
+ } else if (status.battery_warning == VEHICLE_BATTERY_WARNING_LOW || status.failsafe) {
/* play tune on battery warning or failsafe */
set_tune(TONE_BATTERY_WARNING_SLOW_TUNE);
@@ -1517,6 +1630,7 @@ int commander_thread_main(int argc, char *argv[])
close(diff_pres_sub);
close(param_changed_sub);
close(battery_sub);
+ close(mission_pub);
thread_running = false;
@@ -1536,22 +1650,22 @@ check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *val
}
void
-control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed)
+control_status_leds(vehicle_status_s *status_local, const actuator_armed_s *actuator_armed, bool changed)
{
/* driving rgbled */
if (changed) {
bool set_normal_color = false;
/* set mode */
- if (status->arming_state == ARMING_STATE_ARMED) {
+ if (status_local->arming_state == ARMING_STATE_ARMED) {
rgbled_set_mode(RGBLED_MODE_ON);
set_normal_color = true;
- } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ } else if (status_local->arming_state == ARMING_STATE_ARMED_ERROR) {
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
rgbled_set_color(RGBLED_COLOR_RED);
- } else if (status->arming_state == ARMING_STATE_STANDBY) {
+ } else if (status_local->arming_state == ARMING_STATE_STANDBY) {
rgbled_set_mode(RGBLED_MODE_BREATHE);
set_normal_color = true;
@@ -1562,12 +1676,12 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
if (set_normal_color) {
/* set color */
- if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status->failsafe_state != FAILSAFE_STATE_NORMAL) {
+ if (status_local->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status_local->failsafe) {
rgbled_set_color(RGBLED_COLOR_AMBER);
/* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */
} else {
- if (status->condition_local_position_valid) {
+ if (status_local->condition_local_position_valid) {
rgbled_set_color(RGBLED_COLOR_GREEN);
} else {
@@ -1600,7 +1714,7 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
#endif
/* give system warnings on error LED, XXX maybe add memory usage warning too */
- if (status->load > 0.95f) {
+ if (status_local->load > 0.95f) {
if (leds_counter % 2 == 0) {
led_toggle(LED_AMBER);
}
@@ -1613,11 +1727,23 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
}
transition_result_t
-set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoint_s *sp_man)
+set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_setpoint_s *sp_man)
{
/* set main state according to RC switches */
transition_result_t res = TRANSITION_DENIED;
+ /* offboard switch overrides main switch */
+ if (sp_man->offboard_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_OFFBOARD);
+ if (res == TRANSITION_DENIED) {
+ print_reject_mode(status_local, "OFFBOARD");
+
+ } else {
+ return res;
+ }
+ }
+
+ /* offboard switched off or denied, check main mode switch */
switch (sp_man->mode_switch) {
case SWITCH_POS_NONE:
res = TRANSITION_NOT_CHANGED;
@@ -1625,58 +1751,100 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
case SWITCH_POS_OFF: // MANUAL
if (sp_man->acro_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_ACRO);
+ res = main_state_transition(status_local, MAIN_STATE_ACRO);
} else {
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
}
// TRANSITION_DENIED is not possible here
break;
case SWITCH_POS_MIDDLE: // ASSIST
if (sp_man->posctl_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_POSCTL);
+ res = main_state_transition(status_local, MAIN_STATE_POSCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to ALTCTL
- print_reject_mode(status, "POSCTL");
+ print_reject_mode(status_local, "POSCTL");
}
- res = main_state_transition(status, MAIN_STATE_ALTCTL);
+ // fallback to ALTCTL
+ res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
if (sp_man->posctl_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "ALTCTL");
+ print_reject_mode(status_local, "ALTCTL");
}
- // else fallback to MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ // fallback to MANUAL
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
// TRANSITION_DENIED is not possible here
break;
case SWITCH_POS_ON: // AUTO
- res = main_state_transition(status, MAIN_STATE_AUTO);
+ if (sp_man->return_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_RTL);
- if (res != TRANSITION_DENIED) {
- break; // changed successfully or already in this state
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ print_reject_mode(status_local, "AUTO_RTL");
+
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ } else if (sp_man->loiter_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ print_reject_mode(status_local, "AUTO_LOITER");
+
+ } else {
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ print_reject_mode(status_local, "AUTO_MISSION");
+
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
}
- // else fallback to ALTCTL (POSCTL likely will not work too)
- print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_ALTCTL);
+ // fallback to POSCTL
+ res = main_state_transition(status_local, MAIN_STATE_POSCTL);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
+
+ // fallback to ALTCTL
+ res = main_state_transition(status_local, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ // fallback to MANUAL
+ res = main_state_transition(status_local, MAIN_STATE_MANUAL);
// TRANSITION_DENIED is not possible here
break;
@@ -1688,47 +1856,83 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
}
void
-
set_control_mode()
{
- /* set vehicle_control_mode according to main state and failsafe state */
+ /* set vehicle_control_mode according to set_navigation_state */
control_mode.flag_armed = armed.armed;
+ /* TODO: check this */
control_mode.flag_external_manual_override_ok = !status.is_rotary_wing;
control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON;
+ control_mode.flag_control_offboard_enabled = false;
- control_mode.flag_control_termination_enabled = false;
+ switch (status.nav_state) {
+ case NAVIGATION_STATE_MANUAL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = status.is_rotary_wing;
+ control_mode.flag_control_attitude_enabled = status.is_rotary_wing;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
- /* set this flag when navigator should act */
- bool navigator_enabled = false;
+ case NAVIGATION_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
- switch (status.failsafe_state) {
- case FAILSAFE_STATE_NORMAL:
- switch (status.main_state) {
- case MAIN_STATE_MANUAL:
- control_mode.flag_control_manual_enabled = true;
- control_mode.flag_control_auto_enabled = false;
- control_mode.flag_control_rates_enabled = status.is_rotary_wing;
- control_mode.flag_control_attitude_enabled = status.is_rotary_wing;
+ case NAVIGATION_STATE_ALTCTL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ control_mode.flag_control_termination_enabled = false;
+ break;
+
+ case NAVIGATION_STATE_OFFBOARD:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_offboard_enabled = true;
+
+ switch (sp_offboard.mode) {
+ case OFFBOARD_CONTROL_MODE_DIRECT_RATES:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
control_mode.flag_control_altitude_enabled = false;
control_mode.flag_control_climb_rate_enabled = false;
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
-
- case MAIN_STATE_ALTCTL:
- control_mode.flag_control_manual_enabled = true;
- control_mode.flag_control_auto_enabled = false;
+ case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE:
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
- control_mode.flag_control_altitude_enabled = true;
- control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
break;
-
- case MAIN_STATE_POSCTL:
- control_mode.flag_control_manual_enabled = true;
- control_mode.flag_control_auto_enabled = false;
+ case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_velocity_enabled = true;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
control_mode.flag_control_rates_enabled = true;
control_mode.flag_control_attitude_enabled = true;
control_mode.flag_control_altitude_enabled = true;
@@ -1736,37 +1940,57 @@ set_control_mode()
control_mode.flag_control_position_enabled = true;
control_mode.flag_control_velocity_enabled = true;
break;
-
- case MAIN_STATE_AUTO:
- navigator_enabled = true;
- break;
-
- case MAIN_STATE_ACRO:
- control_mode.flag_control_manual_enabled = true;
- control_mode.flag_control_auto_enabled = false;
- control_mode.flag_control_rates_enabled = true;
+ default:
+ control_mode.flag_control_rates_enabled = false;
control_mode.flag_control_attitude_enabled = false;
control_mode.flag_control_altitude_enabled = false;
control_mode.flag_control_climb_rate_enabled = false;
control_mode.flag_control_position_enabled = false;
control_mode.flag_control_velocity_enabled = false;
- break;
-
- default:
- break;
}
+ break;
+ case NAVIGATION_STATE_POSCTL:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ control_mode.flag_control_termination_enabled = false;
break;
- case FAILSAFE_STATE_RTL:
- navigator_enabled = true;
+ case NAVIGATION_STATE_AUTO_MISSION:
+ case NAVIGATION_STATE_AUTO_LOITER:
+ case NAVIGATION_STATE_AUTO_RTL:
+ case NAVIGATION_STATE_AUTO_RTGS:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = true;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ control_mode.flag_control_termination_enabled = false;
break;
- case FAILSAFE_STATE_LAND:
- navigator_enabled = true;
+ case NAVIGATION_STATE_LAND:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = true;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ /* in failsafe LAND mode position may be not available */
+ control_mode.flag_control_position_enabled = status.condition_local_position_valid;
+ control_mode.flag_control_velocity_enabled = status.condition_local_position_valid;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_termination_enabled = false;
break;
- case FAILSAFE_STATE_TERMINATION:
+ case NAVIGATION_STATE_TERMINATION:
/* disable all controllers on termination */
control_mode.flag_control_manual_enabled = false;
control_mode.flag_control_auto_enabled = false;
@@ -1782,33 +2006,16 @@ set_control_mode()
default:
break;
}
-
- /* navigator has control, set control mode flags according to nav state*/
- if (navigator_enabled) {
- control_mode.flag_control_manual_enabled = false;
- control_mode.flag_control_auto_enabled = true;
- control_mode.flag_control_rates_enabled = true;
- control_mode.flag_control_attitude_enabled = true;
-
- /* in failsafe LAND mode position may be not available */
- control_mode.flag_control_position_enabled = status.condition_local_position_valid;
- control_mode.flag_control_velocity_enabled = status.condition_local_position_valid;
-
- control_mode.flag_control_altitude_enabled = true;
- control_mode.flag_control_climb_rate_enabled = true;
- }
}
void
-print_reject_mode(struct vehicle_status_s *status, const char *msg)
+print_reject_mode(struct vehicle_status_s *status_local, const char *msg)
{
hrt_abstime t = hrt_absolute_time();
if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
last_print_mode_reject_time = t;
- char s[80];
- sprintf(s, "#audio: REJECT %s", msg);
- mavlink_log_critical(mavlink_fd, s);
+ mavlink_log_critical(mavlink_fd, "REJECT %s", msg);
/* only buzz if armed, because else we're driving people nuts indoors
they really need to look at the leds as well. */
@@ -1823,9 +2030,7 @@ print_reject_arm(const char *msg)
if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) {
last_print_mode_reject_time = t;
- char s[80];
- sprintf(s, "#audio: %s", msg);
- mavlink_log_critical(mavlink_fd, s);
+ mavlink_log_critical(mavlink_fd, msg);
tune_negative(true);
}
}
@@ -1838,12 +2043,12 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
break;
case VEHICLE_CMD_RESULT_DENIED:
- mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd.command);
+ mavlink_log_critical(mavlink_fd, "command denied: %u", cmd.command);
tune_negative(true);
break;
case VEHICLE_CMD_RESULT_FAILED:
- mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd.command);
+ mavlink_log_critical(mavlink_fd, "command failed: %u", cmd.command);
tune_negative(true);
break;
@@ -1854,7 +2059,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
break;
case VEHICLE_CMD_RESULT_UNSUPPORTED:
- mavlink_log_critical(mavlink_fd, "#audio: command unsupported: %u", cmd.command);
+ mavlink_log_critical(mavlink_fd, "command unsupported: %u", cmd.command);
tune_negative(true);
break;
@@ -1939,9 +2144,7 @@ void *commander_low_prio_loop(void *arg)
int calib_ret = ERROR;
/* try to go to INIT/PREFLIGHT arming state */
-
- // XXX disable interrupts in arming_state_transition
- if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed)) {
+ if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) {
answer_command(cmd, VEHICLE_CMD_RESULT_DENIED);
break;
}
@@ -2004,7 +2207,7 @@ void *commander_low_prio_loop(void *arg)
tune_negative(true);
}
- arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
+ arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd);
break;
}
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index 940a04aa1..d5fe122cb 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -1,9 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,11 @@
/**
* @file commander_helper.cpp
* Commander helper functions implementations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
*/
#include <stdio.h>
@@ -209,12 +211,18 @@ int led_init()
/* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
(void)ioctl(leds, LED_ON, LED_BLUE);
+ /* switch blue off */
+ led_off(LED_BLUE);
+
/* we consider the amber led mandatory */
if (ioctl(leds, LED_ON, LED_AMBER)) {
warnx("Amber LED: ioctl fail\n");
return ERROR;
}
+ /* switch amber off */
+ led_off(LED_AMBER);
+
/* then try RGB LEDs, this can fail on FMUv1*/
rgbleds = open(RGBLED_DEVICE_PATH, 0);
diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h
index e75f2592f..a49c9e263 100644
--- a/src/modules/commander/commander_helper.h
+++ b/src/modules/commander/commander_helper.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * 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
@@ -36,6 +34,9 @@
/**
* @file commander_helper.h
* Commander helper functions definitions
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#ifndef COMMANDER_HELPER_H_
@@ -77,6 +78,8 @@ void rgbled_set_pattern(rgbled_pattern_t *pattern);
* Use integral of current if battery capacity known (BAT_CAPACITY parameter set),
* else use simple estimate based on voltage.
*
+ * @param voltage the current battery voltage
+ * @param discharged the discharged capacity
* @return the estimated remaining capacity in 0..1
*/
float battery_remaining_estimate_voltage(float voltage, float discharged);
diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c
index 80ca68f21..4750f9d5c 100644
--- a/src/modules/commander/commander_params.c
+++ b/src/modules/commander/commander_params.c
@@ -39,7 +39,7 @@
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <nuttx/config.h>
@@ -84,3 +84,14 @@ PARAM_DEFINE_INT32(BAT_N_CELLS, 3);
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f);
+
+/**
+ * Datalink loss mode enabled.
+ *
+ * Set to 1 to enable actions triggered when the datalink is lost.
+ *
+ * @group commander
+ * @min 0
+ * @max 1
+ */
+PARAM_DEFINE_INT32(COM_DL_LOSS_EN, 0);
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index ee0d08391..2e18c4284 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -183,12 +183,12 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
// Safety switch arming tests
- { "transition: init to standby, no safety switch",
+ { "transition: standby to armed, no safety switch",
{ ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_NOT_AVAILABLE, ATT_SAFETY_OFF,
ARMING_STATE_ARMED,
{ ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
- { "transition: init to standby, safety switch off",
+ { "transition: standby to armed, safety switch off",
{ ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_OFF,
ARMING_STATE_ARMED,
{ ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED },
@@ -286,7 +286,7 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
armed.ready_to_arm = test->current_state.ready_to_arm;
// Attempt transition
- transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed);
+ transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, 0 /* no mavlink_fd */);
// Validate result of transition
ut_assert(test->assertMsg, test->expected_transition_result == result);
@@ -300,70 +300,151 @@ bool StateMachineHelperTest::armingStateTransitionTest(void)
bool StateMachineHelperTest::mainStateTransitionTest(void)
{
- struct vehicle_status_s current_state;
- main_state_t new_main_state;
+ // This structure represent a single test case for testing Main State transitions.
+ typedef struct {
+ const char* assertMsg; // Text to show when test case fails
+ uint8_t condition_bits; // Bits for various condition_* values
+ main_state_t from_state; // State prior to transition request
+ main_state_t to_state; // State to transition to
+ transition_result_t expected_transition_result; // Expected result from main_state_transition call
+ } MainTransitionTest_t;
+
+ // Bits for condition_bits
+ #define MTT_ALL_NOT_VALID 0
+ #define MTT_ROTARY_WING 1 << 0
+ #define MTT_LOC_ALT_VALID 1 << 1
+ #define MTT_LOC_POS_VALID 1 << 2
+ #define MTT_HOME_POS_VALID 1 << 3
+ #define MTT_GLOBAL_POS_VALID 1 << 4
+
+ static const MainTransitionTest_t rgMainTransitionTests[] = {
+
+ // TRANSITION_NOT_CHANGED tests
+
+ { "no transition: identical states",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_MANUAL, TRANSITION_NOT_CHANGED },
+
+ // TRANSITION_CHANGED tests
+
+ { "transition: MANUAL to ACRO",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ACRO, TRANSITION_CHANGED },
+
+ { "transition: ACRO to MANUAL",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_ACRO, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_MISSION - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_CHANGED },
+
+ { "transition: AUTO_MISSION to MANUAL - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_AUTO_MISSION, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_LOITER - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_CHANGED },
+
+ { "transition: AUTO_LOITER to MANUAL - global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_AUTO_LOITER, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to AUTO_RTL - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_CHANGED },
+
+ { "transition: AUTO_RTL to MANUAL - global position valid, home position valid",
+ MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID,
+ MAIN_STATE_AUTO_RTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - not rotary",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude valid",
+ MTT_ROTARY_WING | MTT_LOC_ALT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to ALTCTL - rotary, global position valid, local altitude not valid",
+ MTT_ROTARY_WING | MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED },
+
+ { "transition: ALTCTL to MANUAL - local altitude valid",
+ MTT_LOC_ALT_VALID,
+ MAIN_STATE_ALTCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to POSCTL - local position not valid, global position valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED },
+
+ { "transition: MANUAL to POSCTL - local position valid, global position not valid",
+ MTT_LOC_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED },
+
+ { "transition: POSCTL to MANUAL - local position valid, global position valid",
+ MTT_LOC_POS_VALID,
+ MAIN_STATE_POSCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED },
+
+ // TRANSITION_DENIED tests
+
+ { "no transition: MANUAL to AUTO_MISSION - global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_LOITER - global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position not valid, home position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position not valid, home position valid",
+ MTT_HOME_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to AUTO_RTL - global position valid, home position not valid",
+ MTT_GLOBAL_POS_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude not valid",
+ MTT_ROTARY_WING,
+ MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_DENIED },
+
+ { "no transition: MANUAL to POSCTL - local position not valid, global position not valid",
+ MTT_ALL_NOT_VALID,
+ MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_DENIED },
+ };
- // Identical states.
- current_state.main_state = MAIN_STATE_MANUAL;
- new_main_state = MAIN_STATE_MANUAL;
- ut_assert("no transition: identical states",
- TRANSITION_NOT_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
-
- // AUTO to MANUAL.
- current_state.main_state = MAIN_STATE_AUTO;
- new_main_state = MAIN_STATE_MANUAL;
- ut_assert("transition changed: auto to manual",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
-
- // MANUAL to ALTCTRL.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_ALTCTL;
- ut_assert("tranisition: manual to altctrl",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state);
-
- // MANUAL to ALTCTRL, invalid local altitude.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_local_altitude_valid = false;
- new_main_state = MAIN_STATE_ALTCTL;
- ut_assert("no transition: invalid local altitude",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
-
- // MANUAL to POSCTRL.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_POSCTL;
- ut_assert("transition: manual to posctrl",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state);
-
- // MANUAL to POSCTRL, invalid local position.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_local_position_valid = false;
- new_main_state = MAIN_STATE_POSCTL;
- ut_assert("no transition: invalid position",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
-
- // MANUAL to AUTO.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_global_position_valid = true;
- new_main_state = MAIN_STATE_AUTO;
- ut_assert("transition: manual to auto",
- TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: auto", MAIN_STATE_AUTO == current_state.main_state);
-
- // MANUAL to AUTO, invalid global position.
- current_state.main_state = MAIN_STATE_MANUAL;
- current_state.condition_global_position_valid = false;
- new_main_state = MAIN_STATE_AUTO;
- ut_assert("no transition: invalid global position",
- TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
+ size_t cMainTransitionTests = sizeof(rgMainTransitionTests) / sizeof(rgMainTransitionTests[0]);
+ for (size_t i=0; i<cMainTransitionTests; i++) {
+ const MainTransitionTest_t* test = &rgMainTransitionTests[i];
+
+ // Setup initial machine state
+ struct vehicle_status_s current_state;
+ current_state.main_state = test->from_state;
+ current_state.is_rotary_wing = test->condition_bits & MTT_ROTARY_WING;
+ current_state.condition_local_altitude_valid = test->condition_bits & MTT_LOC_ALT_VALID;
+ current_state.condition_local_position_valid = test->condition_bits & MTT_LOC_POS_VALID;
+ current_state.condition_home_position_valid = test->condition_bits & MTT_HOME_POS_VALID;
+ current_state.condition_global_position_valid = test->condition_bits & MTT_GLOBAL_POS_VALID;
+
+ // Attempt transition
+ transition_result_t result = main_state_transition(&current_state, test->to_state);
+
+ // Validate result of transition
+ ut_assert(test->assertMsg, test->expected_transition_result == result);
+ if (test->expected_transition_result == result) {
+ if (test->expected_transition_result == TRANSITION_CHANGED) {
+ ut_assert(test->assertMsg, test->to_state == current_state.main_state);
+ } else {
+ ut_assert(test->assertMsg, test->from_state == current_state.main_state);
+ }
+ }
+ }
+
return true;
}
diff --git a/src/modules/commander/mag_calibration.h b/src/modules/commander/mag_calibration.h
index a101cd7b1..c14f948cc 100644
--- a/src/modules/commander/mag_calibration.h
+++ b/src/modules/commander/mag_calibration.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index e0f8dc95d..eaf309288 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -16,6 +16,7 @@ enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_MAIN_MODE_ACRO,
+ PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
@@ -25,6 +26,7 @@ enum PX4_CUSTOM_SUB_MODE_AUTO {
PX4_CUSTOM_SUB_MODE_AUTO_MISSION,
PX4_CUSTOM_SUB_MODE_AUTO_RTL,
PX4_CUSTOM_SUB_MODE_AUTO_LAND,
+ PX4_CUSTOM_SUB_MODE_AUTO_RTGS
};
union px4_custom_mode {
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 87309b238..372ba9d7d 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * 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
@@ -36,6 +34,9 @@
/**
* @file state_machine_helper.cpp
* State machine helper functions implementations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <stdio.h>
@@ -45,14 +46,19 @@
#include <dirent.h>
#include <fcntl.h>
#include <string.h>
+#include <math.h>
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_controls.h>
+#include <uORB/topics/differential_pressure.h>
+#include <uORB/topics/airspeed.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <drivers/drv_hrt.h>
+#include <drivers/drv_accel.h>
+#include <drivers/drv_airspeed.h>
#include <drivers/drv_device.h>
#include <mavlink/mavlink_log.h>
@@ -65,28 +71,24 @@
#endif
static const int ERROR = -1;
-static bool arming_state_changed = true;
-static bool main_state_changed = true;
-static bool failsafe_state_changed = true;
-
// This array defines the arming state transitions. The rows are the new state, and the columns
// are the current state. Using new state and current state you can index into the array which
// will be true for a valid transition or false for a invalid transition. In some cases even
// though the transition is marked as true additional checks must be made. See arming_state_transition
// code for those checks.
static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
- // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
- { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
- { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
- { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
- { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
- { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
- { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
- { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
};
// You can index into the array with an arming_state_t in order to get it's textual representation
-static const char *state_names[ARMING_STATE_MAX] = {
+static const char * const state_names[ARMING_STATE_MAX] = {
"ARMING_STATE_INIT",
"ARMING_STATE_STANDBY",
"ARMING_STATE_ARMED",
@@ -107,18 +109,31 @@ arming_state_transition(struct vehicle_status_s *status, /// current
ASSERT(ARMING_STATE_INIT == 0);
ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
- /*
- * Perform an atomic state update
- */
- irqstate_t flags = irqsave();
-
transition_result_t ret = TRANSITION_DENIED;
+ arming_state_t current_arming_state = status->arming_state;
+
/* only check transition if the new state is actually different from the current one */
- if (new_arming_state == status->arming_state) {
+ if (new_arming_state == current_arming_state) {
ret = TRANSITION_NOT_CHANGED;
} else {
+
+ /*
+ * Get sensing state if necessary
+ */
+ int prearm_ret = OK;
+
+ /* only perform the check if we have to */
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ prearm_ret = prearm_check(status, mavlink_fd);
+ }
+
+ /*
+ * Perform an atomic state update
+ */
+ irqstate_t flags = irqsave();
+
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
@@ -133,15 +148,44 @@ arming_state_transition(struct vehicle_status_s *status, /// current
if (valid_transition) {
// We have a good transition. Now perform any secondary validation.
if (new_arming_state == ARMING_STATE_ARMED) {
- // Fail transition if we need safety switch press
- // Allow if coming from in air restore
+
+ // Do not perform pre-arm checks if coming from in air restore
// Allow if HIL_STATE_ON
- if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch first.");
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE &&
+ status->hil_state == HIL_STATE_OFF) {
+
+ // Fail transition if pre-arm check fails
+ if (prearm_ret) {
+ valid_transition = false;
+
+ // Fail transition if we need safety switch press
+ } else if (safety->safety_switch_available && !safety->safety_off) {
+
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!");
+
+ valid_transition = false;
+ }
+
+ // Perform power checks only if circuit breaker is not
+ // engaged for these checks
+ if (!status->circuit_breaker_engaged_power_check) {
+ // Fail transition if power is not good
+ if (!status->condition_power_input_valid) {
+
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module.");
+ valid_transition = false;
+ }
+
+ // Fail transition if power levels on the avionics rail
+ // are measured but are insufficient
+ if (status->condition_power_input_valid && ((status->avionics_power_rail_voltage > 0.0f) &&
+ (status->avionics_power_rail_voltage < 4.9f))) {
+
+ mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage);
+ valid_transition = false;
+ }
}
- valid_transition = false;
}
} else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
@@ -165,19 +209,16 @@ arming_state_transition(struct vehicle_status_s *status, /// current
armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
ret = TRANSITION_CHANGED;
status->arming_state = new_arming_state;
- arming_state_changed = true;
}
- }
- /* end of atomic state update */
- irqrestore(flags);
+ /* end of atomic state update */
+ irqrestore(flags);
+ }
if (ret == TRANSITION_DENIED) {
- static const char *errMsg = "Invalid arming transition from %s to %s";
+ static const char *errMsg = "INVAL: %s - %s";
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
}
@@ -199,69 +240,67 @@ bool is_safe(const struct vehicle_status_s *status, const struct safety_s *safet
}
}
-bool
-check_arming_state_changed()
-{
- if (arming_state_changed) {
- arming_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
transition_result_t
main_state_transition(struct vehicle_status_s *status, main_state_t new_main_state)
{
transition_result_t ret = TRANSITION_DENIED;
- /* transition may be denied even if requested the same state because conditions may be changed */
+ /* transition may be denied even if the same state is requested because conditions may have changed */
switch (new_main_state) {
case MAIN_STATE_MANUAL:
- ret = TRANSITION_CHANGED;
- break;
-
case MAIN_STATE_ACRO:
ret = TRANSITION_CHANGED;
break;
case MAIN_STATE_ALTCTL:
-
/* need at minimum altitude estimate */
+ /* TODO: add this for fixedwing as well */
if (!status->is_rotary_wing ||
(status->condition_local_altitude_valid ||
status->condition_global_position_valid)) {
ret = TRANSITION_CHANGED;
}
-
break;
case MAIN_STATE_POSCTL:
-
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
status->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
}
-
break;
- case MAIN_STATE_AUTO:
-
+ case MAIN_STATE_AUTO_LOITER:
/* need global position estimate */
if (status->condition_global_position_valid) {
ret = TRANSITION_CHANGED;
}
+ break;
+
+ case MAIN_STATE_AUTO_MISSION:
+ case MAIN_STATE_AUTO_RTL:
+ /* need global position and home position */
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ ret = TRANSITION_CHANGED;
+ }
+ break;
+
+ case MAIN_STATE_OFFBOARD:
+
+ /* need offboard signal */
+ if (!status->offboard_control_signal_lost) {
+ ret = TRANSITION_CHANGED;
+ }
break;
- }
+ case MAIN_STATE_MAX:
+ default:
+ break;
+ }
if (ret == TRANSITION_CHANGED) {
if (status->main_state != new_main_state) {
status->main_state = new_main_state;
- main_state_changed = true;
-
} else {
ret = TRANSITION_NOT_CHANGED;
}
@@ -270,70 +309,35 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
return ret;
}
-bool
-check_main_state_changed()
-{
- if (main_state_changed) {
- main_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
-bool
-check_failsafe_state_changed()
-{
- if (failsafe_state_changed) {
- failsafe_state_changed = false;
- return true;
-
- } else {
- return false;
- }
-}
-
/**
-* Transition from one hil state to another
-*/
-int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
+ * Transition from one hil state to another
+ */
+transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd)
{
- bool valid_transition = false;
- int ret = ERROR;
+ transition_result_t ret = TRANSITION_DENIED;
if (current_status->hil_state == new_state) {
- valid_transition = true;
+ ret = TRANSITION_NOT_CHANGED;
} else {
-
switch (new_state) {
-
case HIL_STATE_OFF:
-
/* we're in HIL and unexpected things can happen if we disable HIL now */
mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
- valid_transition = false;
-
+ ret = TRANSITION_DENIED;
break;
case HIL_STATE_ON:
-
if (current_status->arming_state == ARMING_STATE_INIT
|| current_status->arming_state == ARMING_STATE_STANDBY
|| current_status->arming_state == ARMING_STATE_STANDBY_ERROR) {
- mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
- valid_transition = true;
-
- // Disable publication of all attached sensors
-
+ /* Disable publication of all attached sensors */
/* list directory */
DIR *d;
d = opendir("/dev");
if (d) {
-
struct dirent *direntry;
char devname[24];
@@ -388,290 +392,296 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
printf("Disabling %s: %s\n", devname, (block_ret == OK) ? "OK" : "ERROR");
}
-
closedir(d);
+ ret = TRANSITION_CHANGED;
+ mavlink_log_critical(mavlink_fd, "Switched to ON hil state");
+
} else {
/* failed opening dir */
- warnx("FAILED LISTING DEVICE ROOT DIRECTORY");
- return 1;
+ mavlink_log_info(mavlink_fd, "FAILED LISTING DEVICE ROOT DIRECTORY");
+ ret = TRANSITION_DENIED;
}
+ } else {
+ mavlink_log_critical(mavlink_fd, "Not switching to HIL when armed");
+ ret = TRANSITION_DENIED;
}
-
break;
default:
- warnx("Unknown hil state");
+ warnx("Unknown HIL state");
break;
}
}
- if (valid_transition) {
+ if (ret == TRANSITION_CHANGED) {
current_status->hil_state = new_state;
-
current_status->timestamp = hrt_absolute_time();
- orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
// XXX also set lockdown here
-
- ret = OK;
-
- } else {
- mavlink_log_critical(mavlink_fd, "REJECTING invalid hil state transition");
+ orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
}
-
return ret;
}
-
/**
-* Transition from one failsafe state to another
-*/
-transition_result_t failsafe_state_transition(struct vehicle_status_s *status, failsafe_state_t new_failsafe_state)
+ * Check failsafe and main status and set navigation status for navigator accordingly
+ */
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished)
{
- transition_result_t ret = TRANSITION_DENIED;
+ navigation_state_t nav_state_old = status->nav_state;
- /* transition may be denied even if requested the same state because conditions may be changed */
- if (status->failsafe_state == FAILSAFE_STATE_TERMINATION) {
- /* transitions from TERMINATION to other states not allowed */
- if (new_failsafe_state == FAILSAFE_STATE_TERMINATION) {
- ret = TRANSITION_NOT_CHANGED;
+ bool armed = (status->arming_state == ARMING_STATE_ARMED || status->arming_state == ARMING_STATE_ARMED_ERROR);
+ status->failsafe = false;
+
+ /* evaluate main state to decide in normal (non-failsafe) mode */
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ case MAIN_STATE_MANUAL:
+ case MAIN_STATE_ALTCTL:
+ case MAIN_STATE_POSCTL:
+ /* require RC for all manual modes */
+ if (status->rc_signal_lost && armed) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ } else {
+ switch (status->main_state) {
+ case MAIN_STATE_ACRO:
+ status->nav_state = NAVIGATION_STATE_ACRO;
+ break;
+
+ case MAIN_STATE_MANUAL:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+
+ case MAIN_STATE_ALTCTL:
+ status->nav_state = NAVIGATION_STATE_ALTCTL;
+ break;
+
+ case MAIN_STATE_POSCTL:
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ break;
+
+ default:
+ status->nav_state = NAVIGATION_STATE_MANUAL;
+ break;
+ }
}
+ break;
- } else {
- switch (new_failsafe_state) {
- case FAILSAFE_STATE_NORMAL:
- /* always allowed (except from TERMINATION state) */
- ret = TRANSITION_CHANGED;
- break;
+ case MAIN_STATE_AUTO_MISSION:
+ /* go into failsafe
+ * - if either the datalink is enabled and lost as well as RC is lost
+ * - if there is no datalink and the mission is finished */
+ if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) ||
+ (!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) {
+ status->failsafe = true;
- case FAILSAFE_STATE_RTL:
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
- /* global position and home position required for RTL */
if (status->condition_global_position_valid && status->condition_home_position_valid) {
- status->set_nav_state = NAV_STATE_RTL;
- status->set_nav_state_timestamp = hrt_absolute_time();
- ret = TRANSITION_CHANGED;
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
}
- break;
+ /* don't bother if RC is lost and mission is not yet finished */
+ } else if (status->rc_signal_lost) {
+
+ /* this mode is ok, we don't need RC for missions */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_MISSION;
+ }
+ break;
- case FAILSAFE_STATE_LAND:
+ case MAIN_STATE_AUTO_LOITER:
+ /* go into failsafe if datalink and RC is lost */
+ if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) {
+ status->failsafe = true;
- /* at least relative altitude estimate required for landing */
- if (status->condition_local_altitude_valid || status->condition_global_position_valid) {
- status->set_nav_state = NAV_STATE_LAND;
- status->set_nav_state_timestamp = hrt_absolute_time();
- ret = TRANSITION_CHANGED;
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
}
- break;
+ /* also go into failsafe if just datalink is lost */
+ } else if (status->data_link_lost && data_link_loss_enabled) {
+ status->failsafe = true;
- case FAILSAFE_STATE_TERMINATION:
- /* always allowed */
- ret = TRANSITION_CHANGED;
- break;
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
- default:
- break;
+ /* go into failsafe if RC is lost and datalink loss is not set up */
+ } else if (status->rc_signal_lost && !data_link_loss_enabled) {
+ status->failsafe = true;
+
+ if (status->condition_global_position_valid && status->condition_home_position_valid) {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTGS;
+ } else if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+
+ /* don't bother if RC is lost if datalink is connected */
+ } else if (status->rc_signal_lost) {
+
+ /* this mode is ok, we don't need RC for loitering */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
+ } else {
+ /* everything is perfect */
+ status->nav_state = NAVIGATION_STATE_AUTO_LOITER;
}
+ break;
- if (ret == TRANSITION_CHANGED) {
- if (status->failsafe_state != new_failsafe_state) {
- status->failsafe_state = new_failsafe_state;
- failsafe_state_changed = true;
+ case MAIN_STATE_AUTO_RTL:
+ /* require global position and home */
+ if ((!status->condition_global_position_valid || !status->condition_home_position_valid)) {
+ status->failsafe = true;
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
} else {
- ret = TRANSITION_NOT_CHANGED;
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
}
+ } else {
+ status->nav_state = NAVIGATION_STATE_AUTO_RTL;
+ }
+ break;
+
+ case MAIN_STATE_OFFBOARD:
+ /* require offboard control, otherwise stay where you are */
+ if (status->offboard_control_signal_lost && !status->rc_signal_lost) {
+ status->failsafe = true;
+
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ } else if (status->offboard_control_signal_lost && status->rc_signal_lost) {
+ status->failsafe = true;
+
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+ } else {
+ status->nav_state = NAVIGATION_STATE_OFFBOARD;
}
+ default:
+ break;
}
- return ret;
+ return status->nav_state != nav_state_old;
}
+int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
+{
+ int ret;
+ bool failed = false;
+
+ int fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
+ if (fd < 0) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL SENSOR MISSING");
+ failed = true;
+ goto system_eval;
+ }
-// /*
-// * Wrapper functions (to be used in the commander), all functions assume lock on current_status
-// */
-
-// /* These functions decide if an emergency exits and then switch to SYSTEM_STATE_MISSION_ABORT or SYSTEM_STATE_GROUND_ERROR
-// *
-// * START SUBSYSTEM/EMERGENCY FUNCTIONS
-// * */
-
-// void update_state_machine_subsystem_present(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_notpresent(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_present &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was removed something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: gyro not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: accelerometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: magnetometer not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV];
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: GPS not present", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-// void update_state_machine_subsystem_enabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled |= 1 << *subsystem_type;
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-// }
-
-// void update_state_machine_subsystem_disabled(int status_pub, struct vehicle_status_s *current_status, subsystem_type_t *subsystem_type)
-// {
-// current_status->onboard_control_sensors_enabled &= ~(1 << *subsystem_type);
-// current_status->counter++;
-// current_status->timestamp = hrt_absolute_time();
-// orb_publish(ORB_ID(vehicle_status), status_pub, current_status);
-
-// /* if a subsystem was disabled something went completely wrong */
-
-// switch (*subsystem_type) {
-// case SUBSYSTEM_TYPE_GYRO:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - gyro disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_ACC:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - accelerometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_MAG:
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - magnetometer disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency_always_critical(status_pub, current_status);
-// break;
-
-// case SUBSYSTEM_TYPE_GPS:
-// {
-// uint8_t flight_env = (uint8_t)(global_data_parameter_storage->pm.param_values[PARAM_FLIGHT_ENV]);
-
-// if (flight_env == PX4_FLIGHT_ENVIRONMENT_OUTDOOR) {
-// //global_data_send_mavlink_statustext_message_out("Commander: EMERGENCY - GPS disabled", MAV_SEVERITY_EMERGENCY);
-// state_machine_emergency(status_pub, current_status);
-// }
-// }
-// break;
-
-// default:
-// break;
-// }
-
-// }
-
-
-///* END SUBSYSTEM/EMERGENCY FUNCTIONS*/
-//
-//int update_state_machine_mode_request(int status_pub, struct vehicle_status_s *current_status, const int mavlink_fd, uint8_t mode)
-//{
-// int ret = 1;
-//
-//// /* Switch on HIL if in standby and not already in HIL mode */
-//// if ((mode & VEHICLE_MODE_FLAG_HIL_ENABLED)
-//// && !current_status->flag_hil_enabled) {
-//// if ((current_status->state_machine == SYSTEM_STATE_STANDBY)) {
-//// /* Enable HIL on request */
-//// current_status->flag_hil_enabled = true;
-//// ret = OK;
-//// state_machine_publish(status_pub, current_status, mavlink_fd);
-//// publish_armed_status(current_status);
-//// printf("[cmd] Enabling HIL, locking down all actuators for safety.\n\t(Arming the system will not activate them while in HIL mode)\n");
-////
-//// } else if (current_status->state_machine != SYSTEM_STATE_STANDBY &&
-//// current_status->flag_fmu_armed) {
-////
-//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, disarm first!")
-////
-//// } else {
-////
-//// mavlink_log_critical(mavlink_fd, "REJECTING HIL, not in standby.")
-//// }
-//// }
-//
-// /* switch manual / auto */
-// if (mode & VEHICLE_MODE_FLAG_AUTO_ENABLED) {
-// update_state_machine_mode_auto(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_STABILIZED_ENABLED) {
-// update_state_machine_mode_stabilized(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_GUIDED_ENABLED) {
-// update_state_machine_mode_guided(status_pub, current_status, mavlink_fd);
-//
-// } else if (mode & VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED) {
-// update_state_machine_mode_manual(status_pub, current_status, mavlink_fd);
-// }
-//
-// /* vehicle is disarmed, mode requests arming */
-// if (!(current_status->flag_fmu_armed) && (mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
-// /* only arm in standby state */
-// // XXX REMOVE
-// if (current_status->state_machine == SYSTEM_STATE_STANDBY || current_status->state_machine == SYSTEM_STATE_PREFLIGHT) {
-// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_GROUND_READY);
-// ret = OK;
-// printf("[cmd] arming due to command request\n");
-// }
-// }
-//
-// /* vehicle is armed, mode requests disarming */
-// if (current_status->flag_fmu_armed && !(mode & VEHICLE_MODE_FLAG_SAFETY_ARMED)) {
-// /* only disarm in ground ready */
-// if (current_status->state_machine == SYSTEM_STATE_GROUND_READY) {
-// do_state_update(status_pub, current_status, mavlink_fd, (commander_state_machine_t)SYSTEM_STATE_STANDBY);
-// ret = OK;
-// printf("[cmd] disarming due to command request\n");
-// }
-// }
-//
-// /* NEVER actually switch off HIL without reboot */
-// if (current_status->flag_hil_enabled && !(mode & VEHICLE_MODE_FLAG_HIL_ENABLED)) {
-// warnx("DENYING request to switch off HIL. Please power cycle (safety reasons)\n");
-// mavlink_log_critical(mavlink_fd, "Power-cycle to exit HIL");
-// ret = ERROR;
-// }
-//
-// return ret;
-//}
+ ret = ioctl(fd, ACCELIOCSELFTEST, 0);
+ if (ret != OK) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL CALIBRATION");
+ failed = true;
+ goto system_eval;
+ }
+
+ /* check measurement result range */
+ struct accel_report acc;
+ ret = read(fd, &acc, sizeof(acc));
+
+ if (ret == sizeof(acc)) {
+ /* evaluate values */
+ float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z);
+
+ if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE");
+ mavlink_log_critical(mavlink_fd, "hold still while arming");
+ /* this is frickin' fatal */
+ failed = true;
+ goto system_eval;
+ }
+ } else {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL READ");
+ /* this is frickin' fatal */
+ failed = true;
+ goto system_eval;
+ }
+
+ if (!status->is_rotary_wing) {
+ /* accel done, close it */
+ close(fd);
+ fd = orb_subscribe(ORB_ID(airspeed));
+
+ struct airspeed_s airspeed;
+
+ if ((ret = orb_copy(ORB_ID(airspeed), fd, &airspeed)) ||
+ (hrt_elapsed_time(&airspeed.timestamp) > (50 * 1000))) {
+ mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED SENSOR MISSING");
+ failed = true;
+ goto system_eval;
+ }
+
+ if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
+ mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION MISSING");
+ // XXX do not make this fatal yet
+ }
+ }
+
+system_eval:
+ close(fd);
+ return (failed);
+}
diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h
index 0ddd4f05a..bb1b87e71 100644
--- a/src/modules/commander/state_machine_helper.h
+++ b/src/modules/commander/state_machine_helper.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
+ * 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
@@ -36,14 +34,14 @@
/**
* @file state_machine_helper.h
* State machine helper functions definitions
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
*/
#ifndef STATE_MACHINE_HELPER_H_
#define STATE_MACHINE_HELPER_H_
-#define GPS_NOFIX_COUNTER_LIMIT 4 //need GPS_NOFIX_COUNTER_LIMIT gps packets with a bad fix to call an error (if outdoor)
-#define GPS_GOTFIX_COUNTER_REQUIRED 4 //need GPS_GOTFIX_COUNTER_REQUIRED gps packets with a good fix to obtain position lock
-
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/actuator_armed.h>
@@ -56,25 +54,17 @@ typedef enum {
} transition_result_t;
-transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
- arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd = 0);
-
bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed);
-bool check_arming_state_changed();
+transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety,
+ arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd);
transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state);
-bool check_main_state_changed();
-
-transition_result_t failsafe_state_transition(struct vehicle_status_s *status, failsafe_state_t new_failsafe_state);
-
-bool check_navigation_state_changed();
-
-bool check_failsafe_state_changed();
+transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
-void set_navigation_state_changed();
+bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished);
-int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_status_s *current_state, const int mavlink_fd);
+int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd);
#endif /* STATE_MACHINE_HELPER_H_ */
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 1a65313e8..ca1fe9bbb 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -50,6 +50,7 @@
#include <string.h>
#include "dataman.h"
+#include <systemlib/param/param.h>
/**
* data manager app start / stop handling function
@@ -61,6 +62,8 @@ __EXPORT int dataman_main(int argc, char *argv[]);
__EXPORT ssize_t dm_read(dm_item_t item, unsigned char index, void *buffer, size_t buflen);
__EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buffer, size_t buflen);
__EXPORT int dm_clear(dm_item_t item);
+__EXPORT void dm_lock(dm_item_t item);
+__EXPORT void dm_unlock(dm_item_t item);
__EXPORT int dm_restart(dm_reset_reason restart_type);
/** Types of function calls supported by the worker task */
@@ -113,12 +116,17 @@ static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = {
DM_KEY_FENCE_POINTS_MAX,
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX,
- DM_KEY_WAYPOINTS_ONBOARD_MAX
+ DM_KEY_WAYPOINTS_ONBOARD_MAX,
+ DM_KEY_MISSION_STATE_MAX
};
/* Table of offset for index 0 of each item type */
static unsigned int g_key_offsets[DM_KEY_NUM_KEYS];
+/* Item type lock mutexes */
+static sem_t *g_item_locks[DM_KEY_NUM_KEYS];
+static sem_t g_sys_state_mutex;
+
/* The data manager store file handle and file name */
static int g_fd = -1, g_task_fd = -1;
static const char *k_data_manager_device_path = "/fs/microsd/dataman";
@@ -138,22 +146,22 @@ static work_q_t g_work_q; /* pending work items. To be consumed by worker thread
sem_t g_work_queued_sema; /* To notify worker thread a work item has been queued */
sem_t g_init_sema;
-static bool g_task_should_exit; /**< if true, dataman task should exit */
+static bool g_task_should_exit; /**< if true, dataman task should exit */
#define DM_SECTOR_HDR_SIZE 4 /* data manager per item header overhead */
static const unsigned k_sector_size = DM_MAX_DATA_SIZE + DM_SECTOR_HDR_SIZE; /* total item sorage space */
static void init_q(work_q_t *q)
{
- sq_init(&(q->q)); /* Initialize the NuttX queue structure */
+ sq_init(&(q->q)); /* Initialize the NuttX queue structure */
sem_init(&(q->mutex), 1, 1); /* Queue is initially unlocked */
- q->size = q->max_size = 0; /* Queue is initially empty */
+ q->size = q->max_size = 0; /* Queue is initially empty */
}
static inline void
destroy_q(work_q_t *q)
{
- sem_destroy(&(q->mutex)); /* Destroy the queue lock */
+ sem_destroy(&(q->mutex)); /* Destroy the queue lock */
}
static inline void
@@ -187,7 +195,7 @@ create_work_item(void)
if (item) {
item->first = 1;
lock_queue(&g_free_q);
- for (int i = 1; i < k_work_item_allocation_chunk_size; i++) {
+ for (size_t i = 1; i < k_work_item_allocation_chunk_size; i++) {
(item + i)->first = 0;
sq_addfirst(&(item + i)->link, &(g_free_q.q));
}
@@ -317,7 +325,9 @@ _write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const v
buffer[1] = persistence;
buffer[2] = 0;
buffer[3] = 0;
- memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
+ if (count > 0) {
+ memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count);
+ }
count += DM_SECTOR_HDR_SIZE;
len = -1;
@@ -567,6 +577,32 @@ dm_clear(dm_item_t item)
return enqueue_work_item_and_wait_for_result(work);
}
+__EXPORT void
+dm_lock(dm_item_t item)
+{
+ /* Make sure data manager has been started and is not shutting down */
+ if ((g_fd < 0) || g_task_should_exit)
+ return;
+ if (item >= DM_KEY_NUM_KEYS)
+ return;
+ if (g_item_locks[item]) {
+ sem_wait(g_item_locks[item]);
+ }
+}
+
+__EXPORT void
+dm_unlock(dm_item_t item)
+{
+ /* Make sure data manager has been started and is not shutting down */
+ if ((g_fd < 0) || g_task_should_exit)
+ return;
+ if (item >= DM_KEY_NUM_KEYS)
+ return;
+ if (g_item_locks[item]) {
+ sem_post(g_item_locks[item]);
+ }
+}
+
/* Tell the data manager about the type of the last reset */
__EXPORT int
dm_restart(dm_reset_reason reason)
@@ -607,6 +643,12 @@ task_main(int argc, char *argv[])
for (unsigned i = 0; i < dm_number_of_funcs; i++)
g_func_counts[i] = 0;
+ /* Initialize the item type locks, for now only DM_KEY_MISSION_STATE supports locking */
+ sem_init(&g_sys_state_mutex, 1, 1); /* Initially unlocked */
+ for (unsigned i = 0; i < DM_KEY_NUM_KEYS; i++)
+ g_item_locks[i] = NULL;
+ g_item_locks[DM_KEY_MISSION_STATE] = &g_sys_state_mutex;
+
g_task_should_exit = false;
init_q(&g_work_q);
@@ -742,6 +784,7 @@ task_main(int argc, char *argv[])
destroy_q(&g_work_q);
destroy_q(&g_free_q);
sem_destroy(&g_work_queued_sema);
+ sem_destroy(&g_sys_state_mutex);
return 0;
}
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index 1dfb26f73..d625bf985 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -53,16 +53,20 @@ extern "C" {
DM_KEY_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */
DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */
DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */
+ DM_KEY_MISSION_STATE, /* Persistent mission state */
DM_KEY_NUM_KEYS /* Total number of item types defined */
} dm_item_t;
+ #define DM_KEY_WAYPOINTS_OFFBOARD(_id) (_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1)
+
/** The maximum number of instances for each item type */
enum {
DM_KEY_SAFE_POINTS_MAX = 8,
DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED,
- DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED
+ DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED,
+ DM_KEY_MISSION_STATE_MAX = 1
};
/** Data persistence levels */
@@ -101,6 +105,18 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
+ /** Lock all items of this type */
+ __EXPORT void
+ dm_lock(
+ dm_item_t item /* The item type to clear */
+ );
+
+ /** Unlock all items of this type */
+ __EXPORT void
+ dm_unlock(
+ dm_item_t item /* The item type to clear */
+ );
+
/** Erase all items of this type */
__EXPORT int
dm_clear(
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index d806b0241..ccc497323 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -49,11 +49,11 @@
#include <math.h>
#include <poll.h>
#include <time.h>
-#include <drivers/drv_hrt.h>
+#include <float.h>
#define SENSOR_COMBINED_SUB
-
+#include <drivers/drv_hrt.h>
#include <drivers/drv_gyro.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_mag.h>
@@ -74,6 +74,7 @@
#include <uORB/topics/estimator_status.h>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/home_position.h>
+#include <uORB/topics/wind_estimate.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
@@ -82,7 +83,7 @@
#include <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>
-#include "estimator.h"
+#include "estimator_23states.h"
@@ -95,7 +96,6 @@ extern "C" __EXPORT int ekf_att_pos_estimator_main(int argc, char *argv[]);
__EXPORT uint32_t millis();
-static uint64_t last_run = 0;
static uint64_t IMUmsec = 0;
static const uint64_t FILTER_INIT_DELAY = 1 * 1000 * 1000;
@@ -112,6 +112,10 @@ public:
*/
FixedwingEstimator();
+ /* we do not want people ever copying this class */
+ FixedwingEstimator(const FixedwingEstimator& that) = delete;
+ FixedwingEstimator operator=(const FixedwingEstimator&) = delete;
+
/**
* Destructor, also kills the sensors task.
*/
@@ -120,11 +124,18 @@ public:
/**
* Start the sensors task.
*
- * @return OK on success.
+ * @return OK on success.
*/
int start();
/**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
+ /**
* Print the current status.
*/
void print_status();
@@ -134,10 +145,25 @@ public:
*/
int trip_nan();
+ /**
+ * Enable logging.
+ *
+ * @param enable Set to true to enable logging, false to disable
+ */
+ int enable_logging(bool enable);
+
+ /**
+ * Set debug level.
+ *
+ * @param debug Desired debug level - 0 to disable.
+ */
+ int set_debuglevel(unsigned debug) { _debug = debug; return 0; }
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
- int _estimator_task; /**< task handle for sensor task */
+ bool _task_running; /**< if true, task is running in its mainloop */
+ int _estimator_task; /**< task handle for sensor task */
#ifndef SENSOR_COMBINED_SUB
int _gyro_sub; /**< gyro sensor subscription */
int _accel_sub; /**< accel sensor subscription */
@@ -158,6 +184,7 @@ private:
orb_advert_t _global_pos_pub; /**< global position */
orb_advert_t _local_pos_pub; /**< position in local frame */
orb_advert_t _estimator_status_pub; /**< status of the estimator */
+ orb_advert_t _wind_pub; /**< wind estimate */
struct vehicle_attitude_s _att; /**< vehicle attitude */
struct gyro_report _gyro;
@@ -169,6 +196,7 @@ private:
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 wind_estimate_s _wind; /**< Wind estimate */
struct gyro_scale _gyro_offsets;
struct accel_scale _accel_offsets;
@@ -181,24 +209,28 @@ private:
struct map_projection_reference_s _pos_ref;
float _baro_ref; /**< barometer reference altitude */
- float _baro_gps_offset; /**< offset between GPS and baro */
+ float _baro_ref_offset; /**< offset between initial baro reference and GPS init baro altitude */
+ float _baro_gps_offset; /**< offset between baro altitude (at GPS init time) and GPS altitude */
- perf_counter_t _loop_perf; /**< loop performance counter */
+ 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
+ perf_counter_t _perf_reset; ///<local performance counter for filter resets
- bool _initialized;
bool _baro_init;
bool _gps_initialized;
- uint64_t _gps_start_time;
- uint64_t _filter_start_time;
+ hrt_abstime _gps_start_time;
+ hrt_abstime _filter_start_time;
+ hrt_abstime _last_sensor_timestamp;
+ hrt_abstime _last_run;
bool _gyro_valid;
bool _accel_valid;
bool _mag_valid;
+ bool _ekf_logging; ///< log EKF state
+ unsigned _debug; ///< debug level - default 0
int _mavlink_fd;
@@ -246,6 +278,10 @@ private:
AttPosEKF *_ekf;
+ float _velocity_xy_filtered;
+ float _velocity_z_filtered;
+ float _airspeed_filtered;
+
/**
* Update our local parameter cache.
*/
@@ -268,9 +304,16 @@ private:
static void task_main_trampoline(int argc, char *argv[]);
/**
- * Main sensor collection task.
+ * Main filter task.
*/
void task_main();
+
+ /**
+ * Check filter sanity state
+ *
+ * @return zero if ok, non-zero for a filter error condition.
+ */
+ int check_filter_state();
};
namespace estimator
@@ -282,12 +325,13 @@ namespace estimator
#endif
static const int ERROR = -1;
-FixedwingEstimator *g_estimator;
+FixedwingEstimator *g_estimator = nullptr;
}
FixedwingEstimator::FixedwingEstimator() :
_task_should_exit(false),
+ _task_running(false),
_estimator_task(-1),
/* subscriptions */
@@ -312,6 +356,7 @@ FixedwingEstimator::FixedwingEstimator() :
_global_pos_pub(-1),
_local_pos_pub(-1),
_estimator_status_pub(-1),
+ _wind_pub(-1),
_att({}),
_gyro({}),
@@ -323,39 +368,52 @@ FixedwingEstimator::FixedwingEstimator() :
_global_pos({}),
_local_pos({}),
_gps({}),
+ _wind({}),
_gyro_offsets({}),
_accel_offsets({}),
_mag_offsets({}),
#ifdef SENSOR_COMBINED_SUB
- _sensor_combined({}),
+ _sensor_combined{},
#endif
+ _pos_ref{},
_baro_ref(0.0f),
+ _baro_ref_offset(0.0f),
_baro_gps_offset(0.0f),
/* performance counters */
- _loop_perf(perf_alloc(PC_COUNT, "ekf_att_pos_estimator")),
- _perf_gyro(perf_alloc(PC_COUNT, "ekf_att_pos_gyro_upd")),
- _perf_accel(perf_alloc(PC_COUNT, "ekf_att_pos_accel_upd")),
- _perf_mag(perf_alloc(PC_COUNT, "ekf_att_pos_mag_upd")),
- _perf_gps(perf_alloc(PC_COUNT, "ekf_att_pos_gps_upd")),
- _perf_baro(perf_alloc(PC_COUNT, "ekf_att_pos_baro_upd")),
- _perf_airspeed(perf_alloc(PC_COUNT, "ekf_att_pos_aspd_upd")),
+ _loop_perf(perf_alloc(PC_ELAPSED, "ekf_att_pos_estimator")),
+ _perf_gyro(perf_alloc(PC_INTERVAL, "ekf_att_pos_gyro_upd")),
+ _perf_mag(perf_alloc(PC_INTERVAL, "ekf_att_pos_mag_upd")),
+ _perf_gps(perf_alloc(PC_INTERVAL, "ekf_att_pos_gps_upd")),
+ _perf_baro(perf_alloc(PC_INTERVAL, "ekf_att_pos_baro_upd")),
+ _perf_airspeed(perf_alloc(PC_INTERVAL, "ekf_att_pos_aspd_upd")),
+ _perf_reset(perf_alloc(PC_COUNT, "ekf_att_pos_reset")),
/* states */
- _initialized(false),
_baro_init(false),
_gps_initialized(false),
+ _gps_start_time(0),
+ _filter_start_time(0),
+ _last_sensor_timestamp(0),
+ _last_run(0),
_gyro_valid(false),
_accel_valid(false),
_mag_valid(false),
+ _ekf_logging(true),
+ _debug(0),
_mavlink_fd(-1),
- _ekf(nullptr)
+ _parameters{},
+ _parameter_handles{},
+ _ekf(nullptr),
+ _velocity_xy_filtered(0.0f),
+ _velocity_z_filtered(0.0f),
+ _airspeed_filtered(0.0f)
{
- last_run = hrt_absolute_time();
+ _last_run = hrt_absolute_time();
_parameter_handles.vel_delay_ms = param_find("PE_VEL_DELAY_MS");
_parameter_handles.pos_delay_ms = param_find("PE_POS_DELAY_MS");
@@ -439,10 +497,20 @@ FixedwingEstimator::~FixedwingEstimator()
} while (_estimator_task != -1);
}
+ delete _ekf;
+
estimator::g_estimator = nullptr;
}
int
+FixedwingEstimator::enable_logging(bool logging)
+{
+ _ekf_logging = logging;
+
+ return 0;
+}
+
+int
FixedwingEstimator::parameters_update()
{
@@ -500,6 +568,120 @@ FixedwingEstimator::vehicle_status_poll()
}
}
+int
+FixedwingEstimator::check_filter_state()
+{
+ /*
+ * CHECK IF THE INPUT DATA IS SANE
+ */
+
+ struct ekf_status_report ekf_report;
+
+ int check = _ekf->CheckAndBound(&ekf_report);
+
+ const char* const feedback[] = { 0,
+ "NaN in states, resetting",
+ "stale IMU data, resetting",
+ "got initial position lock",
+ "excessive gyro offsets",
+ "GPS velocity divergence",
+ "excessive covariances",
+ "unknown condition"};
+
+ // Print out error condition
+ if (check) {
+ unsigned warn_index = static_cast<unsigned>(check);
+ unsigned max_warn_index = (sizeof(feedback) / sizeof(feedback[0]));
+
+ if (max_warn_index < warn_index) {
+ warn_index = max_warn_index;
+ }
+
+ warnx("reset: %s", feedback[warn_index]);
+ mavlink_log_critical(_mavlink_fd, "[ekf] re-init: %s", feedback[warn_index]);
+ }
+
+ struct estimator_status_report rep;
+ memset(&rep, 0, sizeof(rep));
+
+ // If error flag is set, we got a filter reset
+ if (check && ekf_report.error) {
+
+ // Count the reset condition
+ perf_count(_perf_reset);
+
+ } else if (_ekf_logging) {
+ _ekf->GetFilterState(&ekf_report);
+ }
+
+ if (_ekf_logging || check) {
+ rep.timestamp = hrt_absolute_time();
+
+ rep.nan_flags |= (((uint8_t)ekf_report.angNaN) << 0);
+ rep.nan_flags |= (((uint8_t)ekf_report.summedDelVelNaN) << 1);
+ rep.nan_flags |= (((uint8_t)ekf_report.KHNaN) << 2);
+ rep.nan_flags |= (((uint8_t)ekf_report.KHPNaN) << 3);
+ rep.nan_flags |= (((uint8_t)ekf_report.PNaN) << 4);
+ rep.nan_flags |= (((uint8_t)ekf_report.covarianceNaN) << 5);
+ rep.nan_flags |= (((uint8_t)ekf_report.kalmanGainsNaN) << 6);
+ rep.nan_flags |= (((uint8_t)ekf_report.statesNaN) << 7);
+
+ rep.health_flags |= (((uint8_t)ekf_report.velHealth) << 0);
+ rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1);
+ rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2);
+ rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3);
+ // rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4);
+ // rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5);
+ // rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6);
+ // rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7);
+
+ rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0);
+ rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1);
+ rep.timeout_flags |= (((uint8_t)ekf_report.hgtTimeout) << 2);
+ rep.timeout_flags |= (((uint8_t)ekf_report.imuTimeout) << 3);
+
+ if (_debug > 10) {
+
+ if (rep.health_flags < ((1 << 0) | (1 << 1) | (1 << 2) | (1 << 3))) {
+ warnx("health: VEL:%s POS:%s HGT:%s OFFS:%s",
+ ((rep.health_flags & (1 << 0)) ? "OK" : "ERR"),
+ ((rep.health_flags & (1 << 1)) ? "OK" : "ERR"),
+ ((rep.health_flags & (1 << 2)) ? "OK" : "ERR"),
+ ((rep.health_flags & (1 << 3)) ? "OK" : "ERR"));
+ }
+
+ if (rep.timeout_flags) {
+ warnx("timeout: %s%s%s%s",
+ ((rep.timeout_flags & (1 << 0)) ? "VEL " : ""),
+ ((rep.timeout_flags & (1 << 1)) ? "POS " : ""),
+ ((rep.timeout_flags & (1 << 2)) ? "HGT " : ""),
+ ((rep.timeout_flags & (1 << 3)) ? "IMU " : ""));
+ }
+ }
+
+ // Copy all states or at least all that we can fit
+ unsigned ekf_n_states = ekf_report.n_states;
+ unsigned max_states = (sizeof(rep.states) / sizeof(rep.states[0]));
+ rep.n_states = (ekf_n_states < max_states) ? ekf_n_states : max_states;
+
+ for (unsigned i = 0; i < rep.n_states; i++) {
+ rep.states[i] = ekf_report.states[i];
+ }
+
+ for (unsigned i = 0; i < rep.n_states; i++) {
+ rep.states[i] = ekf_report.states[i];
+ }
+
+ if (_estimator_status_pub > 0) {
+ orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &rep);
+ } else {
+ _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &rep);
+ }
+ }
+
+ return check;
+}
+
void
FixedwingEstimator::task_main_trampoline(int argc, char *argv[])
{
@@ -516,7 +698,7 @@ FixedwingEstimator::task_main()
_filter_start_time = hrt_absolute_time();
if (!_ekf) {
- errx(1, "failed allocating EKF filter - out of RAM!");
+ errx(1, "OUT OF MEM!");
}
/*
@@ -544,14 +726,14 @@ FixedwingEstimator::task_main()
#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);
+ orb_set_interval(_sensor_combined_sub, 9);
#endif
/* sets also parameters in the EKF object */
parameters_update();
- Vector3f lastAngRate = {0.0f, 0.0f, 0.0f};
- Vector3f lastAccel = {0.0f, 0.0f, 0.0f};
+ Vector3f lastAngRate;
+ Vector3f lastAccel;
/* wakeup source(s) */
struct pollfd fds[2];
@@ -572,6 +754,15 @@ FixedwingEstimator::task_main()
bool newAdsData = false;
bool newDataMag = false;
+ float posNED[3] = {0.0f, 0.0f, 0.0f}; // North, East Down position (m)
+
+ uint64_t last_gps = 0;
+ _gps.vel_n_m_s = 0.0f;
+ _gps.vel_e_m_s = 0.0f;
+ _gps.vel_d_m_s = 0.0f;
+
+ _task_running = true;
+
while (!_task_should_exit) {
/* wait for up to 500ms for data */
@@ -583,7 +774,7 @@ FixedwingEstimator::task_main()
/* 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);
+ warn("POLL ERR %d, %d", pret, errno);
continue;
}
@@ -609,8 +800,6 @@ FixedwingEstimator::task_main()
bool accel_updated;
bool mag_updated;
- hrt_abstime last_sensor_timestamp;
-
perf_count(_perf_gyro);
/* Reset baro reference if switching to HIL, reset sensor states */
@@ -634,12 +823,12 @@ FixedwingEstimator::task_main()
_baro_init = false;
_gps_initialized = false;
- last_sensor_timestamp = hrt_absolute_time();
- last_run = last_sensor_timestamp;
+ _last_sensor_timestamp = hrt_absolute_time();
+ _last_run = _last_sensor_timestamp;
_ekf->ZeroVariables();
_ekf->dtIMU = 0.01f;
- _filter_start_time = last_sensor_timestamp;
+ _filter_start_time = _last_sensor_timestamp;
/* now skip this loop and get data on the next one, which will also re-init the filter */
continue;
@@ -657,15 +846,14 @@ FixedwingEstimator::task_main()
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;
+ _last_sensor_timestamp = _gyro.timestamp;
IMUmsec = _gyro.timestamp / 1e3f;
- float deltaT = (_gyro.timestamp - last_run) / 1e6f;
- last_run = _gyro.timestamp;
+ float deltaT = (_gyro.timestamp - _last_run) / 1e6f;
+ _last_run = _gyro.timestamp;
/* guard against too large deltaT's */
if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
@@ -725,17 +913,17 @@ FixedwingEstimator::task_main()
// Copy gyro and accel
- last_sensor_timestamp = _sensor_combined.timestamp;
+ _last_sensor_timestamp = _sensor_combined.timestamp;
IMUmsec = _sensor_combined.timestamp / 1e3f;
- float deltaT = (_sensor_combined.timestamp - last_run) / 1e6f;
+ float deltaT = (_sensor_combined.timestamp - _last_run) / 1e6f;
/* guard against too large deltaT's */
if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
deltaT = 0.01f;
}
- last_run = _sensor_combined.timestamp;
+ _last_run = _sensor_combined.timestamp;
// Always store data, independent of init status
/* fill in last data set */
@@ -753,6 +941,7 @@ FixedwingEstimator::task_main()
}
_gyro_valid = true;
+ perf_count(_perf_gyro);
}
if (accel_updated) {
@@ -784,6 +973,8 @@ FixedwingEstimator::task_main()
#endif
+ //warnx("dang: %8.4f %8.4f dvel: %8.4f %8.4f", _ekf->dAngIMU.x, _ekf->dAngIMU.z, _ekf->dVelIMU.x, _ekf->dVelIMU.z);
+
bool airspeed_updated;
orb_check(_airspeed_sub, &airspeed_updated);
@@ -803,7 +994,7 @@ FixedwingEstimator::task_main()
if (gps_updated) {
- uint64_t last_gps = _gps.timestamp_position;
+ last_gps = _gps.timestamp_position;
orb_copy(ORB_ID(vehicle_gps_position), _gps_sub, &_gps);
perf_count(_perf_gps);
@@ -871,6 +1062,8 @@ FixedwingEstimator::task_main()
warnx("ALT REF INIT");
}
+ perf_count(_perf_baro);
+
newHgtData = true;
} else {
newHgtData = false;
@@ -921,127 +1114,39 @@ FixedwingEstimator::task_main()
newDataMag = false;
}
-
- /**
- * CHECK IF THE INPUT DATA IS SANE
+ /*
+ * CHECK IF ITS THE RIGHT TIME TO RUN THINGS ALREADY
*/
- int check = _ekf->CheckAndBound();
-
- const char* ekfname = "[ekf] ";
-
- switch (check) {
- case 0:
- /* all ok */
- break;
- case 1:
- {
- const char* str = "NaN in states, resetting";
- warnx("%s", str);
- mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
- break;
- }
- case 2:
- {
- const char* str = "stale IMU data, resetting";
- warnx("%s", str);
- mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
- break;
- }
- case 3:
- {
- const char* str = "switching to dynamic state";
- warnx("%s", str);
- mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str);
- break;
- }
-
- default:
- {
- const char* str = "unknown reset condition";
- warnx("%s", str);
- mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
- }
- }
-
- // warn on fatal resets
- if (check == 1) {
- warnx("NUMERIC ERROR IN FILTER");
- }
-
- // If non-zero, we got a filter reset
- if (check) {
-
- struct ekf_status_report ekf_report;
-
- _ekf->GetLastErrorState(&ekf_report);
-
- struct estimator_status_report rep;
- memset(&rep, 0, sizeof(rep));
- rep.timestamp = hrt_absolute_time();
-
- rep.states_nan = ekf_report.statesNaN;
- rep.covariance_nan = ekf_report.covarianceNaN;
- rep.kalman_gain_nan = ekf_report.kalmanGainsNaN;
-
- // Copy all states or at least all that we can fit
- unsigned i = 0;
- unsigned ekf_n_states = (sizeof(ekf_report.states) / sizeof(ekf_report.states[0]));
- unsigned max_states = (sizeof(rep.states) / sizeof(rep.states[0]));
- rep.n_states = (ekf_n_states < max_states) ? ekf_n_states : max_states;
-
- while ((i < ekf_n_states) && (i < max_states)) {
-
- rep.states[i] = ekf_report.states[i];
- i++;
- }
-
- if (_estimator_status_pub > 0) {
- orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &rep);
- } else {
- _estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &rep);
- }
-
- /* set sensors to de-initialized state */
- _gyro_valid = false;
- _accel_valid = false;
- _mag_valid = false;
-
- _baro_init = false;
- _gps_initialized = false;
- last_sensor_timestamp = hrt_absolute_time();
- last_run = last_sensor_timestamp;
-
- _ekf->ZeroVariables();
- _ekf->dtIMU = 0.01f;
-
- // Let the system re-initialize itself
+ if (hrt_elapsed_time(&_filter_start_time) < FILTER_INIT_DELAY) {
continue;
-
}
-
/**
* PART TWO: EXECUTE THE FILTER
+ *
+ * We run the filter only once all data has been fetched
**/
- if ((hrt_elapsed_time(&_filter_start_time) > FILTER_INIT_DELAY) && _baro_init && _gyro_valid && _accel_valid && _mag_valid) {
+ if (_baro_init && _gyro_valid && _accel_valid && _mag_valid) {
float initVelNED[3];
- if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph_m < _parameters.pos_stddev_threshold && _gps.epv_m < _parameters.pos_stddev_threshold) {
-
- initVelNED[0] = _gps.vel_n_m_s;
- initVelNED[1] = _gps.vel_e_m_s;
- initVelNED[2] = _gps.vel_d_m_s;
+ /* Initialize the filter first */
+ if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) {
// GPS is in scaled integers, convert
double lat = _gps.lat / 1.0e7;
double lon = _gps.lon / 1.0e7;
float gps_alt = _gps.alt / 1e3f;
+ initVelNED[0] = _gps.vel_n_m_s;
+ initVelNED[1] = _gps.vel_e_m_s;
+ initVelNED[2] = _gps.vel_d_m_s;
+
// Set up height correctly
orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro);
- _baro_gps_offset = _baro_ref - _baro.altitude;
+ _baro_ref_offset = _ekf->states[9]; // this should become zero in the local frame
+ _baro_gps_offset = _baro.altitude - gps_alt;
_ekf->baroHgt = _baro.altitude;
_ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref));
@@ -1065,10 +1170,13 @@ FixedwingEstimator::task_main()
map_projection_init(&_pos_ref, lat, lon);
mavlink_log_info(_mavlink_fd, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt);
+
+ #if 0
warnx("HOME/REF: LA %8.4f,LO %8.4f,ALT %8.2f V: %8.4f %8.4f %8.4f", lat, lon, (double)gps_alt,
(double)_ekf->velNED[0], (double)_ekf->velNED[1], (double)_ekf->velNED[2]);
- warnx("BARO: %8.4f m / ref: %8.4f m / gps offs: %8.4f m", (double)_ekf->baroHgt, (double)_baro_ref, (double)_baro_gps_offset);
- warnx("GPS: eph: %8.4f, epv: %8.4f, declination: %8.4f", (double)_gps.eph_m, (double)_gps.epv_m, (double)math::degrees(declination));
+ warnx("BARO: %8.4f m / ref: %8.4f m / gps offs: %8.4f m", (double)_ekf->baroHgt, (double)_baro_ref, (double)_baro_ref_offset);
+ warnx("GPS: eph: %8.4f, epv: %8.4f, declination: %8.4f", (double)_gps.eph, (double)_gps.epv, (double)math::degrees(declination));
+ #endif
_gps_initialized = true;
@@ -1077,264 +1185,327 @@ FixedwingEstimator::task_main()
initVelNED[0] = 0.0f;
initVelNED[1] = 0.0f;
initVelNED[2] = 0.0f;
- _ekf->posNED[0] = 0.0f;
- _ekf->posNED[1] = 0.0f;
- _ekf->posNED[2] = 0.0f;
-
- _ekf->posNE[0] = _ekf->posNED[0];
- _ekf->posNE[1] = _ekf->posNED[1];
+ _ekf->posNE[0] = posNED[0];
+ _ekf->posNE[1] = posNED[1];
_local_pos.ref_alt = _baro_ref;
+ _baro_ref_offset = 0.0f;
_baro_gps_offset = 0.0f;
_ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f);
- }
- }
-
- // If valid IMU data and states initialised, predict states and covariances
- if (_ekf->statesInitialised) {
- // Run the strapdown INS equations every IMU update
- _ekf->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
- _ekf->StoreStates(IMUmsec);
- // Check if on ground - status is used by covariance prediction
- _ekf->OnGroundCheck();
- // sum delta angles and time used by covariance prediction
- _ekf->summedDelAng = _ekf->summedDelAng + _ekf->correctedDelAng;
- _ekf->summedDelVel = _ekf->summedDelVel + _ekf->dVelIMU;
- dt += _ekf->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 >= (_ekf->covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > _ekf->covDelAngMax)) {
- _ekf->CovariancePrediction(dt);
- _ekf->summedDelAng.zero();
- _ekf->summedDelVel.zero();
- dt = 0.0f;
- }
-
- _initialized = true;
- }
- // Fuse GPS Measurements
- if (newDataGps && _gps_initialized) {
- // Convert GPS measurements to Pos NE, hgt and Vel NED
- _ekf->velNED[0] = _gps.vel_n_m_s;
- _ekf->velNED[1] = _gps.vel_e_m_s;
- _ekf->velNED[2] = _gps.vel_d_m_s;
- _ekf->calcposNED(_ekf->posNED, _ekf->gpsLat, _ekf->gpsLon, _ekf->gpsHgt, _ekf->latRef, _ekf->lonRef, _ekf->hgtRef);
-
- _ekf->posNE[0] = _ekf->posNED[0];
- _ekf->posNE[1] = _ekf->posNED[1];
- // set fusion flags
- _ekf->fuseVelData = true;
- _ekf->fusePosData = true;
- // recall states stored at time of measurement after adjusting for delays
- _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
- _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
- // run the fusion step
- _ekf->FuseVelposNED();
-
- } else if (_ekf->statesInitialised) {
- // Convert GPS measurements to Pos NE, hgt and Vel NED
- _ekf->velNED[0] = 0.0f;
- _ekf->velNED[1] = 0.0f;
- _ekf->velNED[2] = 0.0f;
- _ekf->posNED[0] = 0.0f;
- _ekf->posNED[1] = 0.0f;
- _ekf->posNED[2] = 0.0f;
-
- _ekf->posNE[0] = _ekf->posNED[0];
- _ekf->posNE[1] = _ekf->posNED[1];
- // set fusion flags
- _ekf->fuseVelData = true;
- _ekf->fusePosData = true;
- // recall states stored at time of measurement after adjusting for delays
- _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
- _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
- // run the fusion step
- _ekf->FuseVelposNED();
+ } else if (_ekf->statesInitialised) {
- } else {
- _ekf->fuseVelData = false;
- _ekf->fusePosData = false;
- }
+ // We're apparently initialized in this case now
+ int check = check_filter_state();
- if (newHgtData && _ekf->statesInitialised) {
- // Could use a blend of GPS and baro alt data if desired
- _ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref);
- _ekf->fuseHgtData = true;
- // recall states stored at time of measurement after adjusting for delays
- _ekf->RecallStates(_ekf->statesAtHgtTime, (IMUmsec - _parameters.height_delay_ms));
- // run the fusion step
- _ekf->FuseVelposNED();
+ if (check) {
+ // Let the system re-initialize itself
+ continue;
+ }
- } else {
- _ekf->fuseHgtData = false;
- }
+ // Run the strapdown INS equations every IMU update
+ _ekf->UpdateStrapdownEquationsNED();
+ #if 0
+ // debug code - could be tunred into a filter mnitoring/watchdog function
+ float tempQuat[4];
- // Fuse Magnetometer Measurements
- if (newDataMag && _ekf->statesInitialised) {
- _ekf->fuseMagData = true;
- _ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data
+ for (uint8_t j = 0; j <= 3; j++) tempQuat[j] = states[j];
- } else {
- _ekf->fuseMagData = false;
- }
+ quat2eul(eulerEst, tempQuat);
- if (_ekf->statesInitialised) _ekf->FuseMagnetometer();
+ for (uint8_t j = 0; j <= 2; j++) eulerDif[j] = eulerEst[j] - ahrsEul[j];
- // Fuse Airspeed Measurements
- if (newAdsData && _ekf->statesInitialised && _ekf->VtasMeas > 8.0f) {
- _ekf->fuseVtasData = true;
- _ekf->RecallStates(_ekf->statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data
- _ekf->FuseAirspeed();
+ if (eulerDif[2] > pi) eulerDif[2] -= 2 * pi;
- } else {
- _ekf->fuseVtasData = false;
- }
+ if (eulerDif[2] < -pi) eulerDif[2] += 2 * pi;
- // Publish results
- if (_initialized && (check == OK)) {
-
-
-
- // 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(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->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] = _ekf->states[0];
- _att.q[1] = _ekf->states[1];
- _att.q[2] = _ekf->states[2];
- _att.q[3] = _ekf->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 = _ekf->angRate.x - _ekf->states[10];
- _att.pitchspeed = _ekf->angRate.y - _ekf->states[11];
- _att.yawspeed = _ekf->angRate.z - _ekf->states[12];
- // gyro offsets
- _att.rate_offsets[0] = _ekf->states[10];
- _att.rate_offsets[1] = _ekf->states[11];
- _att.rate_offsets[2] = _ekf->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);
+ #endif
+ // store the predicted states for subsequent use by measurement fusion
+ _ekf->StoreStates(IMUmsec);
+ // Check if on ground - status is used by covariance prediction
+ _ekf->OnGroundCheck();
+ // sum delta angles and time used by covariance prediction
+ _ekf->summedDelAng = _ekf->summedDelAng + _ekf->correctedDelAng;
+ _ekf->summedDelVel = _ekf->summedDelVel + _ekf->dVelIMU;
+ dt += _ekf->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 >= (_ekf->covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > _ekf->covDelAngMax)) {
+ _ekf->CovariancePrediction(dt);
+ _ekf->summedDelAng.zero();
+ _ekf->summedDelVel.zero();
+ dt = 0.0f;
+ }
- } else {
- /* advertise and publish */
- _att_pub = orb_advertise(ORB_ID(vehicle_attitude), &_att);
- }
- }
+ // Fuse GPS Measurements
+ if (newDataGps && _gps_initialized) {
+ // Convert GPS measurements to Pos NE, hgt and Vel NED
+
+ float gps_dt = (_gps.timestamp_position - last_gps) / 1e6f;
+
+ // Calculate acceleration predicted by GPS velocity change
+ if (((fabsf(_ekf->velNED[0] - _gps.vel_n_m_s) > FLT_EPSILON) ||
+ (fabsf(_ekf->velNED[1] - _gps.vel_e_m_s) > FLT_EPSILON) ||
+ (fabsf(_ekf->velNED[2] - _gps.vel_d_m_s) > FLT_EPSILON)) && (gps_dt > 0.00001f)) {
+
+ _ekf->accelGPSNED[0] = (_ekf->velNED[0] - _gps.vel_n_m_s) / gps_dt;
+ _ekf->accelGPSNED[1] = (_ekf->velNED[1] - _gps.vel_e_m_s) / gps_dt;
+ _ekf->accelGPSNED[2] = (_ekf->velNED[2] - _gps.vel_d_m_s) / gps_dt;
+ }
+
+ _ekf->velNED[0] = _gps.vel_n_m_s;
+ _ekf->velNED[1] = _gps.vel_e_m_s;
+ _ekf->velNED[2] = _gps.vel_d_m_s;
+ _ekf->calcposNED(posNED, _ekf->gpsLat, _ekf->gpsLon, _ekf->gpsHgt, _ekf->latRef, _ekf->lonRef, _ekf->hgtRef);
+
+ _ekf->posNE[0] = posNED[0];
+ _ekf->posNE[1] = posNED[1];
+ // set fusion flags
+ _ekf->fuseVelData = true;
+ _ekf->fusePosData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
+ _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
+ // run the fusion step
+ _ekf->FuseVelposNED();
+
+ } else if (!_gps_initialized) {
+
+ // force static mode
+ _ekf->staticMode = true;
+
+ // Convert GPS measurements to Pos NE, hgt and Vel NED
+ _ekf->velNED[0] = 0.0f;
+ _ekf->velNED[1] = 0.0f;
+ _ekf->velNED[2] = 0.0f;
+
+ _ekf->posNE[0] = 0.0f;
+ _ekf->posNE[1] = 0.0f;
+ // set fusion flags
+ _ekf->fuseVelData = true;
+ _ekf->fusePosData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ _ekf->RecallStates(_ekf->statesAtVelTime, (IMUmsec - _parameters.vel_delay_ms));
+ _ekf->RecallStates(_ekf->statesAtPosTime, (IMUmsec - _parameters.pos_delay_ms));
+ // run the fusion step
+ _ekf->FuseVelposNED();
+
+ } else {
+ _ekf->fuseVelData = false;
+ _ekf->fusePosData = false;
+ }
- if (_gps_initialized) {
- _local_pos.timestamp = last_sensor_timestamp;
- _local_pos.x = _ekf->states[7];
- _local_pos.y = _ekf->states[8];
- // XXX need to announce change of Z reference somehow elegantly
- _local_pos.z = _ekf->states[9] - _baro_gps_offset;
+ if (newHgtData) {
+ // Could use a blend of GPS and baro alt data if desired
+ _ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref);
+ _ekf->fuseHgtData = true;
+ // recall states stored at time of measurement after adjusting for delays
+ _ekf->RecallStates(_ekf->statesAtHgtTime, (IMUmsec - _parameters.height_delay_ms));
+ // run the fusion step
+ _ekf->FuseVelposNED();
+
+ } else {
+ _ekf->fuseHgtData = false;
+ }
- _local_pos.vx = _ekf->states[4];
- _local_pos.vy = _ekf->states[5];
- _local_pos.vz = _ekf->states[6];
+ // Fuse Magnetometer Measurements
+ if (newDataMag) {
+ _ekf->fuseMagData = true;
+ _ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data
- _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;
+ _ekf->magstate.obsIndex = 0;
+ _ekf->FuseMagnetometer();
+ _ekf->FuseMagnetometer();
+ _ekf->FuseMagnetometer();
- _local_pos.z_global = false;
- _local_pos.yaw = _att.yaw;
+ } else {
+ _ekf->fuseMagData = 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);
+ // Fuse Airspeed Measurements
+ if (newAdsData && _ekf->VtasMeas > 7.0f) {
+ _ekf->fuseVtasData = true;
+ _ekf->RecallStates(_ekf->statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data
+ _ekf->FuseAirspeed();
- } else {
- /* advertise and publish */
- _local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &_local_pos);
- }
+ } else {
+ _ekf->fuseVtasData = false;
+ }
- _global_pos.timestamp = _local_pos.timestamp;
- if (_local_pos.xy_global) {
- double est_lat, est_lon;
- map_projection_reproject(&_pos_ref, _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;
- _global_pos.eph = _gps.eph_m;
- _global_pos.epv = _gps.epv_m;
- }
+ // Output results
+ math::Quaternion q(_ekf->states[0], _ekf->states[1], _ekf->states[2], _ekf->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] = _ekf->states[0];
+ _att.q[1] = _ekf->states[1];
+ _att.q[2] = _ekf->states[2];
+ _att.q[3] = _ekf->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 = _ekf->angRate.x - _ekf->states[10];
+ _att.pitchspeed = _ekf->angRate.y - _ekf->states[11];
+ _att.yawspeed = _ekf->angRate.z - _ekf->states[12];
+ // gyro offsets
+ _att.rate_offsets[0] = _ekf->states[10];
+ _att.rate_offsets[1] = _ekf->states[11];
+ _att.rate_offsets[2] = _ekf->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 (_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;
- }
+ if (_gps_initialized) {
+ _local_pos.timestamp = _last_sensor_timestamp;
+ _local_pos.x = _ekf->states[7];
+ _local_pos.y = _ekf->states[8];
+ // XXX need to announce change of Z reference somehow elegantly
+ _local_pos.z = _ekf->states[9] - _baro_ref_offset;
+
+ _local_pos.vx = _ekf->states[4];
+ _local_pos.vy = _ekf->states[5];
+ _local_pos.vz = _ekf->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;
+
+ _velocity_xy_filtered = 0.95f*_velocity_xy_filtered + 0.05f*sqrtf(_local_pos.vx*_local_pos.vx + _local_pos.vy*_local_pos.vy);
+ _velocity_z_filtered = 0.95f*_velocity_z_filtered + 0.05f*fabsf(_local_pos.vz);
+ _airspeed_filtered = 0.95f*_airspeed_filtered + 0.05f*_airspeed.true_airspeed_m_s;
+
+
+ /* crude land detector for fixedwing only,
+ * TODO: adapt so that it works for both, maybe move to another location
+ */
+ if (_velocity_xy_filtered < 5
+ && _velocity_z_filtered < 10
+ && _airspeed_filtered < 10) {
+ _local_pos.landed = true;
+ } else {
+ _local_pos.landed = false;
+ }
+
+ _local_pos.z_global = false;
+ _local_pos.yaw = _att.yaw;
+
+ /* 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;
+
+ if (_local_pos.xy_global) {
+ double est_lat, est_lon;
+ map_projection_reproject(&_pos_ref, _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;
+ _global_pos.eph = _gps.eph;
+ _global_pos.epv = _gps.epv;
+ }
+
+ 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;
+ }
+
+ /* local pos alt is negative, change sign and add alt offsets */
+ _global_pos.alt = _baro_ref + (-_local_pos.z) - _baro_gps_offset;
+
+ if (_local_pos.v_z_valid) {
+ _global_pos.vel_d = _local_pos.vz;
+ }
+
+
+ _global_pos.yaw = _local_pos.yaw;
+
+ _global_pos.eph = _gps.eph;
+ _global_pos.epv = _gps.epv;
+
+ _global_pos.timestamp = _local_pos.timestamp;
+
+ /* lazily publish the global position only once available */
+ if (_global_pos_pub > 0) {
+ /* publish the global position */
+ 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);
+ }
+
+ if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
+ _wind.timestamp = _global_pos.timestamp;
+ _wind.windspeed_north = _ekf->states[14];
+ _wind.windspeed_east = _ekf->states[15];
+ _wind.covariance_north = 0.0f; // XXX get form filter
+ _wind.covariance_east = 0.0f;
+
+ /* lazily publish the wind estimate only once available */
+ if (_wind_pub > 0) {
+ /* publish the wind estimate */
+ orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);
+
+ } else {
+ /* advertise and publish */
+ _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
+ }
+
+ }
+
+ if (hrt_elapsed_time(&_wind.timestamp) > 99000) {
+ _wind.timestamp = _global_pos.timestamp;
+ _wind.windspeed_north = _ekf->states[14];
+ _wind.windspeed_east = _ekf->states[15];
+ _wind.covariance_north = _ekf->P[14][14];
+ _wind.covariance_east = _ekf->P[15][15];
+
+ /* lazily publish the wind estimate only once available */
+ if (_wind_pub > 0) {
+ /* publish the wind estimate */
+ orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind);
+
+ } else {
+ /* advertise and publish */
+ _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind);
+ }
+ }
- /* local pos alt is negative, change sign and add alt offsets */
- _global_pos.alt = _local_pos.ref_alt + _baro_gps_offset + (-_local_pos.z);
+ }
- if (_local_pos.v_z_valid) {
- _global_pos.vel_d = _local_pos.vz;
}
- _global_pos.yaw = _local_pos.yaw;
-
- _global_pos.eph = _gps.eph_m;
- _global_pos.epv = _gps.epv_m;
-
- _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);
- }
}
}
@@ -1342,6 +1513,8 @@ FixedwingEstimator::task_main()
perf_end(_loop_perf);
}
+ _task_running = false;
+
warnx("exiting.\n");
_estimator_task = -1;
@@ -1357,7 +1530,7 @@ FixedwingEstimator::start()
_estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 6000,
+ 5000,
(main_t)&FixedwingEstimator::task_main_trampoline,
nullptr);
@@ -1384,32 +1557,44 @@ FixedwingEstimator::print_status()
// 4-6: Velocity - m/sec (North, East, Down)
// 7-9: Position - m (North, East, Down)
// 10-12: Delta Angle bias - rad (X,Y,Z)
- // 13-14: Wind Vector - m/sec (North,East)
- // 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
- // 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
+ // 13: Accelerometer offset
+ // 14-15: Wind Vector - m/sec (North,East)
+ // 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
+ // 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)
printf("dtIMU: %8.6f IMUmsec: %d\n", (double)_ekf->dtIMU, (int)IMUmsec);
- printf("ref alt: %8.6f\n", (double)_local_pos.ref_alt);
+ printf("baro alt: %8.4f GPS alt: %8.4f\n", (double)_baro.altitude, (double)(_gps.alt / 1e3f));
+ printf("ref alt: %8.4f baro ref offset: %8.4f baro GPS offset: %8.4f\n", (double)_baro_ref, (double)_baro_ref_offset, (double)_baro_gps_offset);
printf("dvel: %8.6f %8.6f %8.6f accel: %8.6f %8.6f %8.6f\n", (double)_ekf->dVelIMU.x, (double)_ekf->dVelIMU.y, (double)_ekf->dVelIMU.z, (double)_ekf->accel.x, (double)_ekf->accel.y, (double)_ekf->accel.z);
printf("dang: %8.4f %8.4f %8.4f dang corr: %8.4f %8.4f %8.4f\n" , (double)_ekf->dAngIMU.x, (double)_ekf->dAngIMU.y, (double)_ekf->dAngIMU.z, (double)_ekf->correctedDelAng.x, (double)_ekf->correctedDelAng.y, (double)_ekf->correctedDelAng.z);
- printf("states (quat) [1-4]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[0], (double)_ekf->states[1], (double)_ekf->states[2], (double)_ekf->states[3]);
- printf("states (vel m/s) [5-7]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[4], (double)_ekf->states[5], (double)_ekf->states[6]);
- printf("states (pos m) [8-10]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[7], (double)_ekf->states[8], (double)_ekf->states[9]);
- printf("states (delta ang) [11-13]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[10], (double)_ekf->states[11], (double)_ekf->states[12]);
- printf("states (wind) [14-15]: %8.4f, %8.4f\n", (double)_ekf->states[13], (double)_ekf->states[14]);
- printf("states (earth mag) [16-18]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[15], (double)_ekf->states[16], (double)_ekf->states[17]);
- printf("states (body mag) [19-21]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[18], (double)_ekf->states[19], (double)_ekf->states[20]);
+ printf("states (quat) [0-3]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[0], (double)_ekf->states[1], (double)_ekf->states[2], (double)_ekf->states[3]);
+ printf("states (vel m/s) [4-6]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[4], (double)_ekf->states[5], (double)_ekf->states[6]);
+ printf("states (pos m) [7-9]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[7], (double)_ekf->states[8], (double)_ekf->states[9]);
+ printf("states (delta ang) [10-12]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[10], (double)_ekf->states[11], (double)_ekf->states[12]);
+
+ if (n_states == 23) {
+ printf("states (accel offs) [13]: %8.4f\n", (double)_ekf->states[13]);
+ printf("states (wind) [14-15]: %8.4f, %8.4f\n", (double)_ekf->states[14], (double)_ekf->states[15]);
+ printf("states (earth mag) [16-18]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[16], (double)_ekf->states[17], (double)_ekf->states[18]);
+ printf("states (body mag) [19-21]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[19], (double)_ekf->states[20], (double)_ekf->states[21]);
+ printf("states (terrain) [22]: %8.4f\n", (double)_ekf->states[22]);
+
+ } else {
+ printf("states (wind) [13-14]: %8.4f, %8.4f\n", (double)_ekf->states[13], (double)_ekf->states[14]);
+ printf("states (earth mag) [15-17]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[15], (double)_ekf->states[16], (double)_ekf->states[17]);
+ printf("states (body mag) [18-20]: %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[18], (double)_ekf->states[19], (double)_ekf->states[20]);
+ }
printf("states: %s %s %s %s %s %s %s %s %s %s\n",
- (_ekf->statesInitialised) ? "INITIALIZED" : "NON_INIT",
- (_ekf->onGround) ? "ON_GROUND" : "AIRBORNE",
- (_ekf->fuseVelData) ? "FUSE_VEL" : "INH_VEL",
- (_ekf->fusePosData) ? "FUSE_POS" : "INH_POS",
- (_ekf->fuseHgtData) ? "FUSE_HGT" : "INH_HGT",
- (_ekf->fuseMagData) ? "FUSE_MAG" : "INH_MAG",
- (_ekf->fuseVtasData) ? "FUSE_VTAS" : "INH_VTAS",
- (_ekf->useAirspeed) ? "USE_AIRSPD" : "IGN_AIRSPD",
- (_ekf->useCompass) ? "USE_COMPASS" : "IGN_COMPASS",
- (_ekf->staticMode) ? "STATIC_MODE" : "DYNAMIC_MODE");
+ (_ekf->statesInitialised) ? "INITIALIZED" : "NON_INIT",
+ (_ekf->onGround) ? "ON_GROUND" : "AIRBORNE",
+ (_ekf->fuseVelData) ? "FUSE_VEL" : "INH_VEL",
+ (_ekf->fusePosData) ? "FUSE_POS" : "INH_POS",
+ (_ekf->fuseHgtData) ? "FUSE_HGT" : "INH_HGT",
+ (_ekf->fuseMagData) ? "FUSE_MAG" : "INH_MAG",
+ (_ekf->fuseVtasData) ? "FUSE_VTAS" : "INH_VTAS",
+ (_ekf->useAirspeed) ? "USE_AIRSPD" : "IGN_AIRSPD",
+ (_ekf->useCompass) ? "USE_COMPASS" : "IGN_COMPASS",
+ (_ekf->staticMode) ? "STATIC_MODE" : "DYNAMIC_MODE");
}
int FixedwingEstimator::trip_nan() {
@@ -1464,7 +1649,7 @@ int FixedwingEstimator::trip_nan() {
int ekf_att_pos_estimator_main(int argc, char *argv[])
{
if (argc < 1)
- errx(1, "usage: ekf_att_pos_estimator {start|stop|status}");
+ errx(1, "usage: ekf_att_pos_estimator {start|stop|status|logging}");
if (!strcmp(argv[1], "start")) {
@@ -1482,6 +1667,14 @@ int ekf_att_pos_estimator_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (estimator::g_estimator == nullptr || !estimator::g_estimator->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}
@@ -1518,6 +1711,29 @@ int ekf_att_pos_estimator_main(int argc, char *argv[])
}
}
+ if (!strcmp(argv[1], "logging")) {
+ if (estimator::g_estimator) {
+ int ret = estimator::g_estimator->enable_logging(true);
+
+ exit(ret);
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
+ if (!strcmp(argv[1], "debug")) {
+ if (estimator::g_estimator) {
+ int debug = strtoul(argv[2], NULL, 10);
+ int ret = estimator::g_estimator->set_debuglevel(debug);
+
+ exit(ret);
+
+ } else {
+ errx(1, "not running");
+ }
+ }
+
warnx("unrecognized command");
return 1;
}
diff --git a/src/modules/ekf_att_pos_estimator/estimator_21states.cpp b/src/modules/ekf_att_pos_estimator/estimator_21states.cpp
new file mode 100644
index 000000000..67bfec4ea
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/estimator_21states.cpp
@@ -0,0 +1,2142 @@
+#include "estimator_21states.h"
+
+#include <string.h>
+
+AttPosEKF::AttPosEKF() :
+ fusionModeGPS(0),
+ covSkipCount(0),
+ EAS2TAS(1.0f),
+ statesInitialised(false),
+ fuseVelData(false),
+ fusePosData(false),
+ fuseHgtData(false),
+ fuseMagData(false),
+ fuseVtasData(false),
+ onGround(true),
+ staticMode(true),
+ useAirspeed(true),
+ useCompass(true),
+ numericalProtection(true),
+ storeIndex(0),
+ magDeclination(0.0f)
+{
+ InitialiseParameters();
+}
+
+AttPosEKF::~AttPosEKF()
+{
+}
+
+void AttPosEKF::UpdateStrapdownEquationsNED()
+{
+ Vector3f delVelNav;
+ float q00;
+ float q11;
+ float q22;
+ float q33;
+ float q01;
+ float q02;
+ float q03;
+ float q12;
+ float q13;
+ float q23;
+ Mat3f Tbn;
+ Mat3f Tnb;
+ float rotationMag;
+ float qUpdated[4];
+ float quatMag;
+ double deltaQuat[4];
+ const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS};
+
+// Remove sensor bias errors
+ correctedDelAng.x = dAngIMU.x - states[10];
+ correctedDelAng.y = dAngIMU.y - states[11];
+ correctedDelAng.z = dAngIMU.z - states[12];
+ dVelIMU.x = dVelIMU.x;
+ dVelIMU.y = dVelIMU.y;
+ dVelIMU.z = dVelIMU.z;
+
+// Save current measurements
+ Vector3f prevDelAng = correctedDelAng;
+
+// Apply corrections for earths rotation rate and coning errors
+// * and + operators have been overloaded
+ correctedDelAng = correctedDelAng - Tnb*earthRateNED*dtIMU + 8.333333333333333e-2f*(prevDelAng % correctedDelAng);
+// Convert the rotation vector to its equivalent quaternion
+ rotationMag = correctedDelAng.length();
+ if (rotationMag < 1e-12f)
+ {
+ deltaQuat[0] = 1.0;
+ deltaQuat[1] = 0.0;
+ deltaQuat[2] = 0.0;
+ deltaQuat[3] = 0.0;
+ }
+ else
+ {
+ deltaQuat[0] = cos(0.5f*rotationMag);
+ double rotScaler = (sin(0.5f*rotationMag))/rotationMag;
+ deltaQuat[1] = correctedDelAng.x*rotScaler;
+ deltaQuat[2] = correctedDelAng.y*rotScaler;
+ deltaQuat[3] = correctedDelAng.z*rotScaler;
+ }
+
+// Update the quaternions by rotating from the previous attitude through
+// the delta angle rotation quaternion
+ qUpdated[0] = states[0]*deltaQuat[0] - states[1]*deltaQuat[1] - states[2]*deltaQuat[2] - states[3]*deltaQuat[3];
+ qUpdated[1] = states[0]*deltaQuat[1] + states[1]*deltaQuat[0] + states[2]*deltaQuat[3] - states[3]*deltaQuat[2];
+ qUpdated[2] = states[0]*deltaQuat[2] + states[2]*deltaQuat[0] + states[3]*deltaQuat[1] - states[1]*deltaQuat[3];
+ qUpdated[3] = states[0]*deltaQuat[3] + states[3]*deltaQuat[0] + states[1]*deltaQuat[2] - states[2]*deltaQuat[1];
+
+// Normalise the quaternions and update the quaternion states
+ quatMag = sqrtf(sq(qUpdated[0]) + sq(qUpdated[1]) + sq(qUpdated[2]) + sq(qUpdated[3]));
+ if (quatMag > 1e-16f)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[0] = quatMagInv*qUpdated[0];
+ states[1] = quatMagInv*qUpdated[1];
+ states[2] = quatMagInv*qUpdated[2];
+ states[3] = quatMagInv*qUpdated[3];
+ }
+
+// Calculate the body to nav cosine matrix
+ q00 = sq(states[0]);
+ q11 = sq(states[1]);
+ q22 = sq(states[2]);
+ q33 = sq(states[3]);
+ q01 = states[0]*states[1];
+ q02 = states[0]*states[2];
+ q03 = states[0]*states[3];
+ q12 = states[1]*states[2];
+ q13 = states[1]*states[3];
+ q23 = states[2]*states[3];
+
+ Tbn.x.x = q00 + q11 - q22 - q33;
+ Tbn.y.y = q00 - q11 + q22 - q33;
+ Tbn.z.z = q00 - q11 - q22 + q33;
+ Tbn.x.y = 2*(q12 - q03);
+ Tbn.x.z = 2*(q13 + q02);
+ Tbn.y.x = 2*(q12 + q03);
+ Tbn.y.z = 2*(q23 - q01);
+ Tbn.z.x = 2*(q13 - q02);
+ Tbn.z.y = 2*(q23 + q01);
+
+ Tnb = Tbn.transpose();
+
+// transform body delta velocities to delta velocities in the nav frame
+// * and + operators have been overloaded
+ //delVelNav = Tbn*dVelIMU + gravityNED*dtIMU;
+ delVelNav.x = Tbn.x.x*dVelIMU.x + Tbn.x.y*dVelIMU.y + Tbn.x.z*dVelIMU.z + gravityNED.x*dtIMU;
+ delVelNav.y = Tbn.y.x*dVelIMU.x + Tbn.y.y*dVelIMU.y + Tbn.y.z*dVelIMU.z + gravityNED.y*dtIMU;
+ delVelNav.z = Tbn.z.x*dVelIMU.x + Tbn.z.y*dVelIMU.y + Tbn.z.z*dVelIMU.z + gravityNED.z*dtIMU;
+
+// calculate the magnitude of the nav acceleration (required for GPS
+// variance estimation)
+ accNavMag = delVelNav.length()/dtIMU;
+
+// If calculating position save previous velocity
+ float lastVelocity[3];
+ lastVelocity[0] = states[4];
+ lastVelocity[1] = states[5];
+ lastVelocity[2] = states[6];
+
+// Sum delta velocities to get velocity
+ states[4] = states[4] + delVelNav.x;
+ states[5] = states[5] + delVelNav.y;
+ states[6] = states[6] + delVelNav.z;
+
+// If calculating postions, do a trapezoidal integration for position
+ states[7] = states[7] + 0.5f*(states[4] + lastVelocity[0])*dtIMU;
+ states[8] = states[8] + 0.5f*(states[5] + lastVelocity[1])*dtIMU;
+ states[9] = states[9] + 0.5f*(states[6] + lastVelocity[2])*dtIMU;
+
+ // Constrain states (to protect against filter divergence)
+ //ConstrainStates();
+}
+
+void AttPosEKF::CovariancePrediction(float dt)
+{
+ // scalars
+ float daxCov;
+ float dayCov;
+ float dazCov;
+ float dvxCov;
+ float dvyCov;
+ float dvzCov;
+ float dvx;
+ float dvy;
+ float dvz;
+ float dax;
+ float day;
+ float daz;
+ float q0;
+ float q1;
+ float q2;
+ float q3;
+ float dax_b;
+ float day_b;
+ float daz_b;
+
+ // arrays
+ float processNoise[21];
+ float SF[14];
+ float SG[8];
+ float SQ[11];
+ float SPP[13] = {0};
+ float nextP[21][21];
+
+ // calculate covariance prediction process noise
+ windVelSigma = dt*0.1f;
+ dAngBiasSigma = dt*5.0e-7f;
+ magEarthSigma = dt*3.0e-4f;
+ magBodySigma = dt*3.0e-4f;
+ for (uint8_t i= 0; i<=9; i++) processNoise[i] = 1.0e-9f;
+ for (uint8_t i=10; i<=12; i++) processNoise[i] = dAngBiasSigma;
+ if (onGround) processNoise[12] = dAngBiasSigma * yawVarScale;
+ for (uint8_t i=13; i<=14; i++) processNoise[i] = windVelSigma;
+ for (uint8_t i=15; i<=17; i++) processNoise[i] = magEarthSigma;
+ for (uint8_t i=18; i<=20; i++) processNoise[i] = magBodySigma;
+ for (uint8_t i= 0; i<=20; i++) processNoise[i] = sq(processNoise[i]);
+
+ // set variables used to calculate covariance growth
+ dvx = summedDelVel.x;
+ dvy = summedDelVel.y;
+ dvz = summedDelVel.z;
+ dax = summedDelAng.x;
+ day = summedDelAng.y;
+ daz = summedDelAng.z;
+ q0 = states[0];
+ q1 = states[1];
+ q2 = states[2];
+ q3 = states[3];
+ dax_b = states[10];
+ day_b = states[11];
+ daz_b = states[12];
+ daxCov = sq(dt*1.4544411e-2f);
+ dayCov = sq(dt*1.4544411e-2f);
+ dazCov = sq(dt*1.4544411e-2f);
+ if (onGround) dazCov = dazCov * sq(yawVarScale);
+ dvxCov = sq(dt*0.5f);
+ dvyCov = sq(dt*0.5f);
+ dvzCov = sq(dt*0.5f);
+
+ // Predicted covariance calculation
+ SF[0] = 2*dvx*q1 + 2*dvy*q2 + 2*dvz*q3;
+ SF[1] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
+ SF[2] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
+ SF[3] = day/2 - day_b/2;
+ SF[4] = daz/2 - daz_b/2;
+ SF[5] = dax/2 - dax_b/2;
+ SF[6] = dax_b/2 - dax/2;
+ SF[7] = daz_b/2 - daz/2;
+ SF[8] = day_b/2 - day/2;
+ SF[9] = q1/2;
+ SF[10] = q2/2;
+ SF[11] = q3/2;
+ SF[12] = 2*dvz*q0;
+ SF[13] = 2*dvy*q1;
+
+ SG[0] = q0/2;
+ SG[1] = sq(q3);
+ SG[2] = sq(q2);
+ SG[3] = sq(q1);
+ SG[4] = sq(q0);
+ SG[5] = 2*q2*q3;
+ SG[6] = 2*q1*q3;
+ SG[7] = 2*q1*q2;
+
+ SQ[0] = dvzCov*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyCov*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxCov*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3);
+ SQ[1] = dvzCov*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxCov*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyCov*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3);
+ SQ[2] = dvzCov*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyCov*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxCov*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]);
+ SQ[3] = (dayCov*q1*SG[0])/2 - (dazCov*q1*SG[0])/2 - (daxCov*q2*q3)/4;
+ SQ[4] = (dazCov*q2*SG[0])/2 - (daxCov*q2*SG[0])/2 - (dayCov*q1*q3)/4;
+ SQ[5] = (daxCov*q3*SG[0])/2 - (dayCov*q3*SG[0])/2 - (dazCov*q1*q2)/4;
+ SQ[6] = (daxCov*q1*q2)/4 - (dazCov*q3*SG[0])/2 - (dayCov*q1*q2)/4;
+ SQ[7] = (dazCov*q1*q3)/4 - (daxCov*q1*q3)/4 - (dayCov*q2*SG[0])/2;
+ SQ[8] = (dayCov*q2*q3)/4 - (daxCov*q1*SG[0])/2 - (dazCov*q2*q3)/4;
+ SQ[9] = sq(SG[0]);
+ SQ[10] = sq(q1);
+
+ SPP[0] = SF[12] + SF[13] - 2*dvx*q2;
+ SPP[1] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
+ SPP[2] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
+ SPP[3] = SF[11];
+ SPP[4] = SF[10];
+ SPP[5] = SF[9];
+ SPP[6] = SF[7];
+ SPP[7] = SF[8];
+
+ nextP[0][0] = P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3] + (daxCov*SQ[10])/4 + SF[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[7]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[6]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[5]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[4]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) + SPP[3]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) + (dayCov*sq(q2))/4 + (dazCov*sq(q3))/4;
+ nextP[0][1] = P[0][1] + SQ[8] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3] + SF[5]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[4]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[7]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[3]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - SPP[4]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]))/2;
+ nextP[0][2] = P[0][2] + SQ[7] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3] + SF[3]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[5]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) - SPP[3]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[5]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]))/2;
+ nextP[0][3] = P[0][3] + SQ[6] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3] + SF[4]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[3]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[6]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[4]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) - SPP[5]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - (q0*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]))/2;
+ nextP[0][4] = P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3] + SF[2]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) - SPP[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]);
+ nextP[0][5] = P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3] + SF[1]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SF[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) - SPP[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]);
+ nextP[0][6] = P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3] + SF[1]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[0]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[0]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) - SPP[1]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]);
+ nextP[0][7] = P[0][7] + P[1][7]*SF[6] + P[2][7]*SPP[7] + P[3][7]*SPP[6] + P[10][7]*SPP[5] + P[11][7]*SPP[4] + P[12][7]*SPP[3] + dt*(P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3]);
+ nextP[0][8] = P[0][8] + P[1][8]*SF[6] + P[2][8]*SPP[7] + P[3][8]*SPP[6] + P[10][8]*SPP[5] + P[11][8]*SPP[4] + P[12][8]*SPP[3] + dt*(P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3]);
+ nextP[0][9] = P[0][9] + P[1][9]*SF[6] + P[2][9]*SPP[7] + P[3][9]*SPP[6] + P[10][9]*SPP[5] + P[11][9]*SPP[4] + P[12][9]*SPP[3] + dt*(P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3]);
+ nextP[0][10] = P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3];
+ nextP[0][11] = P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3];
+ nextP[0][12] = P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3];
+ nextP[0][13] = P[0][13] + P[1][13]*SF[6] + P[2][13]*SPP[7] + P[3][13]*SPP[6] + P[10][13]*SPP[5] + P[11][13]*SPP[4] + P[12][13]*SPP[3];
+ nextP[0][14] = P[0][14] + P[1][14]*SF[6] + P[2][14]*SPP[7] + P[3][14]*SPP[6] + P[10][14]*SPP[5] + P[11][14]*SPP[4] + P[12][14]*SPP[3];
+ nextP[0][15] = P[0][15] + P[1][15]*SF[6] + P[2][15]*SPP[7] + P[3][15]*SPP[6] + P[10][15]*SPP[5] + P[11][15]*SPP[4] + P[12][15]*SPP[3];
+ nextP[0][16] = P[0][16] + P[1][16]*SF[6] + P[2][16]*SPP[7] + P[3][16]*SPP[6] + P[10][16]*SPP[5] + P[11][16]*SPP[4] + P[12][16]*SPP[3];
+ nextP[0][17] = P[0][17] + P[1][17]*SF[6] + P[2][17]*SPP[7] + P[3][17]*SPP[6] + P[10][17]*SPP[5] + P[11][17]*SPP[4] + P[12][17]*SPP[3];
+ nextP[0][18] = P[0][18] + P[1][18]*SF[6] + P[2][18]*SPP[7] + P[3][18]*SPP[6] + P[10][18]*SPP[5] + P[11][18]*SPP[4] + P[12][18]*SPP[3];
+ nextP[0][19] = P[0][19] + P[1][19]*SF[6] + P[2][19]*SPP[7] + P[3][19]*SPP[6] + P[10][19]*SPP[5] + P[11][19]*SPP[4] + P[12][19]*SPP[3];
+ nextP[0][20] = P[0][20] + P[1][20]*SF[6] + P[2][20]*SPP[7] + P[3][20]*SPP[6] + P[10][20]*SPP[5] + P[11][20]*SPP[4] + P[12][20]*SPP[3];
+ nextP[1][0] = P[1][0] + SQ[8] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2 + SF[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[7]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[6]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[5]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[4]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) + SPP[3]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2);
+ nextP[1][1] = P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] + daxCov*SQ[9] - (P[10][1]*q0)/2 + SF[5]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[4]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[7]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[3]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - SPP[4]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) + (dayCov*sq(q3))/4 + (dazCov*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2))/2;
+ nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2 + SF[3]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[5]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) - SPP[3]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[5]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2))/2;
+ nextP[1][3] = P[1][3] + SQ[4] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[3]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[6]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[4]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) - SPP[5]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - (q0*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2))/2;
+ nextP[1][4] = P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2 + SF[2]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) - SPP[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2);
+ nextP[1][5] = P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2 + SF[1]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SF[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) - SPP[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2);
+ nextP[1][6] = P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2 + SF[1]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[0]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[0]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) - SPP[1]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2);
+ nextP[1][7] = P[1][7] + P[0][7]*SF[5] + P[2][7]*SF[4] + P[3][7]*SPP[7] + P[11][7]*SPP[3] - P[12][7]*SPP[4] - (P[10][7]*q0)/2 + dt*(P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2);
+ nextP[1][8] = P[1][8] + P[0][8]*SF[5] + P[2][8]*SF[4] + P[3][8]*SPP[7] + P[11][8]*SPP[3] - P[12][8]*SPP[4] - (P[10][8]*q0)/2 + dt*(P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2);
+ nextP[1][9] = P[1][9] + P[0][9]*SF[5] + P[2][9]*SF[4] + P[3][9]*SPP[7] + P[11][9]*SPP[3] - P[12][9]*SPP[4] - (P[10][9]*q0)/2 + dt*(P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2);
+ nextP[1][10] = P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2;
+ nextP[1][11] = P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2;
+ nextP[1][12] = P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2;
+ nextP[1][13] = P[1][13] + P[0][13]*SF[5] + P[2][13]*SF[4] + P[3][13]*SPP[7] + P[11][13]*SPP[3] - P[12][13]*SPP[4] - (P[10][13]*q0)/2;
+ nextP[1][14] = P[1][14] + P[0][14]*SF[5] + P[2][14]*SF[4] + P[3][14]*SPP[7] + P[11][14]*SPP[3] - P[12][14]*SPP[4] - (P[10][14]*q0)/2;
+ nextP[1][15] = P[1][15] + P[0][15]*SF[5] + P[2][15]*SF[4] + P[3][15]*SPP[7] + P[11][15]*SPP[3] - P[12][15]*SPP[4] - (P[10][15]*q0)/2;
+ nextP[1][16] = P[1][16] + P[0][16]*SF[5] + P[2][16]*SF[4] + P[3][16]*SPP[7] + P[11][16]*SPP[3] - P[12][16]*SPP[4] - (P[10][16]*q0)/2;
+ nextP[1][17] = P[1][17] + P[0][17]*SF[5] + P[2][17]*SF[4] + P[3][17]*SPP[7] + P[11][17]*SPP[3] - P[12][17]*SPP[4] - (P[10][17]*q0)/2;
+ nextP[1][18] = P[1][18] + P[0][18]*SF[5] + P[2][18]*SF[4] + P[3][18]*SPP[7] + P[11][18]*SPP[3] - P[12][18]*SPP[4] - (P[10][18]*q0)/2;
+ nextP[1][19] = P[1][19] + P[0][19]*SF[5] + P[2][19]*SF[4] + P[3][19]*SPP[7] + P[11][19]*SPP[3] - P[12][19]*SPP[4] - (P[10][19]*q0)/2;
+ nextP[1][20] = P[1][20] + P[0][20]*SF[5] + P[2][20]*SF[4] + P[3][20]*SPP[7] + P[11][20]*SPP[3] - P[12][20]*SPP[4] - (P[10][20]*q0)/2;
+ nextP[2][0] = P[2][0] + SQ[7] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2 + SF[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[7]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[6]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[5]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[4]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) + SPP[3]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2);
+ nextP[2][1] = P[2][1] + SQ[5] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2 + SF[5]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[4]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[7]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[3]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - SPP[4]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) - (q0*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2))/2;
+ nextP[2][2] = P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] + dayCov*SQ[9] + (dazCov*SQ[10])/4 - (P[11][2]*q0)/2 + SF[3]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[5]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) - SPP[3]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[5]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) + (daxCov*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2))/2;
+ nextP[2][3] = P[2][3] + SQ[3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[3]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[6]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[4]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) - SPP[5]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - (q0*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2))/2;
+ nextP[2][4] = P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2 + SF[2]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) - SPP[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2);
+ nextP[2][5] = P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2 + SF[1]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SF[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) - SPP[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2);
+ nextP[2][6] = P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2 + SF[1]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[0]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[0]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) - SPP[1]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2);
+ nextP[2][7] = P[2][7] + P[0][7]*SF[3] + P[3][7]*SF[5] + P[1][7]*SPP[6] - P[10][7]*SPP[3] + P[12][7]*SPP[5] - (P[11][7]*q0)/2 + dt*(P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2);
+ nextP[2][8] = P[2][8] + P[0][8]*SF[3] + P[3][8]*SF[5] + P[1][8]*SPP[6] - P[10][8]*SPP[3] + P[12][8]*SPP[5] - (P[11][8]*q0)/2 + dt*(P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2);
+ nextP[2][9] = P[2][9] + P[0][9]*SF[3] + P[3][9]*SF[5] + P[1][9]*SPP[6] - P[10][9]*SPP[3] + P[12][9]*SPP[5] - (P[11][9]*q0)/2 + dt*(P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2);
+ nextP[2][10] = P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2;
+ nextP[2][11] = P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2;
+ nextP[2][12] = P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2;
+ nextP[2][13] = P[2][13] + P[0][13]*SF[3] + P[3][13]*SF[5] + P[1][13]*SPP[6] - P[10][13]*SPP[3] + P[12][13]*SPP[5] - (P[11][13]*q0)/2;
+ nextP[2][14] = P[2][14] + P[0][14]*SF[3] + P[3][14]*SF[5] + P[1][14]*SPP[6] - P[10][14]*SPP[3] + P[12][14]*SPP[5] - (P[11][14]*q0)/2;
+ nextP[2][15] = P[2][15] + P[0][15]*SF[3] + P[3][15]*SF[5] + P[1][15]*SPP[6] - P[10][15]*SPP[3] + P[12][15]*SPP[5] - (P[11][15]*q0)/2;
+ nextP[2][16] = P[2][16] + P[0][16]*SF[3] + P[3][16]*SF[5] + P[1][16]*SPP[6] - P[10][16]*SPP[3] + P[12][16]*SPP[5] - (P[11][16]*q0)/2;
+ nextP[2][17] = P[2][17] + P[0][17]*SF[3] + P[3][17]*SF[5] + P[1][17]*SPP[6] - P[10][17]*SPP[3] + P[12][17]*SPP[5] - (P[11][17]*q0)/2;
+ nextP[2][18] = P[2][18] + P[0][18]*SF[3] + P[3][18]*SF[5] + P[1][18]*SPP[6] - P[10][18]*SPP[3] + P[12][18]*SPP[5] - (P[11][18]*q0)/2;
+ nextP[2][19] = P[2][19] + P[0][19]*SF[3] + P[3][19]*SF[5] + P[1][19]*SPP[6] - P[10][19]*SPP[3] + P[12][19]*SPP[5] - (P[11][19]*q0)/2;
+ nextP[2][20] = P[2][20] + P[0][20]*SF[3] + P[3][20]*SF[5] + P[1][20]*SPP[6] - P[10][20]*SPP[3] + P[12][20]*SPP[5] - (P[11][20]*q0)/2;
+ nextP[3][0] = P[3][0] + SQ[6] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2 + SF[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[7]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[6]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[5]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[4]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + SPP[3]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2);
+ nextP[3][1] = P[3][1] + SQ[4] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2 + SF[5]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[4]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[7]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[3]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) - SPP[4]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2))/2;
+ nextP[3][2] = P[3][2] + SQ[3] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2 + SF[3]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[5]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) - SPP[3]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[5]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2))/2;
+ nextP[3][3] = P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] + (dayCov*SQ[10])/4 + dazCov*SQ[9] - (P[12][3]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[3]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[6]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[4]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) - SPP[5]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + (daxCov*sq(q2))/4 - (q0*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2))/2;
+ nextP[3][4] = P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2 + SF[2]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) - SPP[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2);
+ nextP[3][5] = P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2 + SF[1]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SF[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) - SPP[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2);
+ nextP[3][6] = P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2 + SF[1]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[0]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[0]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) - SPP[1]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2);
+ nextP[3][7] = P[3][7] + P[0][7]*SF[4] + P[1][7]*SF[3] + P[2][7]*SF[6] + P[10][7]*SPP[4] - P[11][7]*SPP[5] - (P[12][7]*q0)/2 + dt*(P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2);
+ nextP[3][8] = P[3][8] + P[0][8]*SF[4] + P[1][8]*SF[3] + P[2][8]*SF[6] + P[10][8]*SPP[4] - P[11][8]*SPP[5] - (P[12][8]*q0)/2 + dt*(P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2);
+ nextP[3][9] = P[3][9] + P[0][9]*SF[4] + P[1][9]*SF[3] + P[2][9]*SF[6] + P[10][9]*SPP[4] - P[11][9]*SPP[5] - (P[12][9]*q0)/2 + dt*(P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2);
+ nextP[3][10] = P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2;
+ nextP[3][11] = P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2;
+ nextP[3][12] = P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2;
+ nextP[3][13] = P[3][13] + P[0][13]*SF[4] + P[1][13]*SF[3] + P[2][13]*SF[6] + P[10][13]*SPP[4] - P[11][13]*SPP[5] - (P[12][13]*q0)/2;
+ nextP[3][14] = P[3][14] + P[0][14]*SF[4] + P[1][14]*SF[3] + P[2][14]*SF[6] + P[10][14]*SPP[4] - P[11][14]*SPP[5] - (P[12][14]*q0)/2;
+ nextP[3][15] = P[3][15] + P[0][15]*SF[4] + P[1][15]*SF[3] + P[2][15]*SF[6] + P[10][15]*SPP[4] - P[11][15]*SPP[5] - (P[12][15]*q0)/2;
+ nextP[3][16] = P[3][16] + P[0][16]*SF[4] + P[1][16]*SF[3] + P[2][16]*SF[6] + P[10][16]*SPP[4] - P[11][16]*SPP[5] - (P[12][16]*q0)/2;
+ nextP[3][17] = P[3][17] + P[0][17]*SF[4] + P[1][17]*SF[3] + P[2][17]*SF[6] + P[10][17]*SPP[4] - P[11][17]*SPP[5] - (P[12][17]*q0)/2;
+ nextP[3][18] = P[3][18] + P[0][18]*SF[4] + P[1][18]*SF[3] + P[2][18]*SF[6] + P[10][18]*SPP[4] - P[11][18]*SPP[5] - (P[12][18]*q0)/2;
+ nextP[3][19] = P[3][19] + P[0][19]*SF[4] + P[1][19]*SF[3] + P[2][19]*SF[6] + P[10][19]*SPP[4] - P[11][19]*SPP[5] - (P[12][19]*q0)/2;
+ nextP[3][20] = P[3][20] + P[0][20]*SF[4] + P[1][20]*SF[3] + P[2][20]*SF[6] + P[10][20]*SPP[4] - P[11][20]*SPP[5] - (P[12][20]*q0)/2;
+ nextP[4][0] = P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2] + SF[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[7]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[6]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[5]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[4]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) + SPP[3]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]);
+ nextP[4][1] = P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2] + SF[5]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[4]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[7]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[3]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - SPP[4]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]))/2;
+ nextP[4][2] = P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2] + SF[3]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[5]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) - SPP[3]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[5]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]))/2;
+ nextP[4][3] = P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2] + SF[4]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[3]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[6]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[4]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) - SPP[5]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - (q0*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]))/2;
+ nextP[4][4] = P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2] + dvyCov*sq(SG[7] - 2*q0*q3) + dvzCov*sq(SG[6] + 2*q0*q2) + SF[2]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) - SPP[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + dvxCov*sq(SG[1] + SG[2] - SG[3] - SG[4]);
+ nextP[4][5] = P[4][5] + SQ[2] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2] + SF[1]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SF[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) - SPP[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]);
+ nextP[4][6] = P[4][6] + SQ[1] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2] + SF[1]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[0]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[0]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) - SPP[1]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]);
+ nextP[4][7] = P[4][7] + P[0][7]*SF[2] + P[1][7]*SF[0] + P[2][7]*SPP[0] - P[3][7]*SPP[2] + dt*(P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2]);
+ nextP[4][8] = P[4][8] + P[0][8]*SF[2] + P[1][8]*SF[0] + P[2][8]*SPP[0] - P[3][8]*SPP[2] + dt*(P[4][5] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2]);
+ nextP[4][9] = P[4][9] + P[0][9]*SF[2] + P[1][9]*SF[0] + P[2][9]*SPP[0] - P[3][9]*SPP[2] + dt*(P[4][6] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2]);
+ nextP[4][10] = P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2];
+ nextP[4][11] = P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2];
+ nextP[4][12] = P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2];
+ nextP[4][13] = P[4][13] + P[0][13]*SF[2] + P[1][13]*SF[0] + P[2][13]*SPP[0] - P[3][13]*SPP[2];
+ nextP[4][14] = P[4][14] + P[0][14]*SF[2] + P[1][14]*SF[0] + P[2][14]*SPP[0] - P[3][14]*SPP[2];
+ nextP[4][15] = P[4][15] + P[0][15]*SF[2] + P[1][15]*SF[0] + P[2][15]*SPP[0] - P[3][15]*SPP[2];
+ nextP[4][16] = P[4][16] + P[0][16]*SF[2] + P[1][16]*SF[0] + P[2][16]*SPP[0] - P[3][16]*SPP[2];
+ nextP[4][17] = P[4][17] + P[0][17]*SF[2] + P[1][17]*SF[0] + P[2][17]*SPP[0] - P[3][17]*SPP[2];
+ nextP[4][18] = P[4][18] + P[0][18]*SF[2] + P[1][18]*SF[0] + P[2][18]*SPP[0] - P[3][18]*SPP[2];
+ nextP[4][19] = P[4][19] + P[0][19]*SF[2] + P[1][19]*SF[0] + P[2][19]*SPP[0] - P[3][19]*SPP[2];
+ nextP[4][20] = P[4][20] + P[0][20]*SF[2] + P[1][20]*SF[0] + P[2][20]*SPP[0] - P[3][20]*SPP[2];
+ nextP[5][0] = P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0] + SF[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[7]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[6]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[5]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[4]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) + SPP[3]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]);
+ nextP[5][1] = P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0] + SF[5]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[4]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[7]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[3]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - SPP[4]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]))/2;
+ nextP[5][2] = P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0] + SF[3]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[5]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) - SPP[3]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[5]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]))/2;
+ nextP[5][3] = P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0] + SF[4]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[3]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[6]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[4]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) - SPP[5]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - (q0*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]))/2;
+ nextP[5][4] = P[5][4] + SQ[2] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0] + SF[2]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) - SPP[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]);
+ nextP[5][5] = P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0] + dvxCov*sq(SG[7] + 2*q0*q3) + dvzCov*sq(SG[5] - 2*q0*q1) + SF[1]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SF[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) - SPP[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + dvyCov*sq(SG[1] - SG[2] + SG[3] - SG[4]);
+ nextP[5][6] = P[5][6] + SQ[0] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0] + SF[1]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[0]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[0]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) - SPP[1]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]);
+ nextP[5][7] = P[5][7] + P[0][7]*SF[1] + P[2][7]*SF[0] + P[3][7]*SF[2] - P[1][7]*SPP[0] + dt*(P[5][4] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0]);
+ nextP[5][8] = P[5][8] + P[0][8]*SF[1] + P[2][8]*SF[0] + P[3][8]*SF[2] - P[1][8]*SPP[0] + dt*(P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0]);
+ nextP[5][9] = P[5][9] + P[0][9]*SF[1] + P[2][9]*SF[0] + P[3][9]*SF[2] - P[1][9]*SPP[0] + dt*(P[5][6] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0]);
+ nextP[5][10] = P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0];
+ nextP[5][11] = P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0];
+ nextP[5][12] = P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0];
+ nextP[5][13] = P[5][13] + P[0][13]*SF[1] + P[2][13]*SF[0] + P[3][13]*SF[2] - P[1][13]*SPP[0];
+ nextP[5][14] = P[5][14] + P[0][14]*SF[1] + P[2][14]*SF[0] + P[3][14]*SF[2] - P[1][14]*SPP[0];
+ nextP[5][15] = P[5][15] + P[0][15]*SF[1] + P[2][15]*SF[0] + P[3][15]*SF[2] - P[1][15]*SPP[0];
+ nextP[5][16] = P[5][16] + P[0][16]*SF[1] + P[2][16]*SF[0] + P[3][16]*SF[2] - P[1][16]*SPP[0];
+ nextP[5][17] = P[5][17] + P[0][17]*SF[1] + P[2][17]*SF[0] + P[3][17]*SF[2] - P[1][17]*SPP[0];
+ nextP[5][18] = P[5][18] + P[0][18]*SF[1] + P[2][18]*SF[0] + P[3][18]*SF[2] - P[1][18]*SPP[0];
+ nextP[5][19] = P[5][19] + P[0][19]*SF[1] + P[2][19]*SF[0] + P[3][19]*SF[2] - P[1][19]*SPP[0];
+ nextP[5][20] = P[5][20] + P[0][20]*SF[1] + P[2][20]*SF[0] + P[3][20]*SF[2] - P[1][20]*SPP[0];
+ nextP[6][0] = P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1] + SF[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[7]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[6]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[5]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[4]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) + SPP[3]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]);
+ nextP[6][1] = P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1] + SF[5]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[4]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[7]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[3]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - SPP[4]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]))/2;
+ nextP[6][2] = P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1] + SF[3]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[5]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) - SPP[3]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[5]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]))/2;
+ nextP[6][3] = P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1] + SF[4]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[3]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[6]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[4]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) - SPP[5]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - (q0*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]))/2;
+ nextP[6][4] = P[6][4] + SQ[1] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1] + SF[2]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) - SPP[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]);
+ nextP[6][5] = P[6][5] + SQ[0] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1] + SF[1]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SF[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) - SPP[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]);
+ nextP[6][6] = P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1] + dvxCov*sq(SG[6] - 2*q0*q2) + dvyCov*sq(SG[5] + 2*q0*q1) + SF[1]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[0]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[0]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) - SPP[1]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + dvzCov*sq(SG[1] - SG[2] - SG[3] + SG[4]);
+ nextP[6][7] = P[6][7] + P[1][7]*SF[1] + P[3][7]*SF[0] + P[0][7]*SPP[0] - P[2][7]*SPP[1] + dt*(P[6][4] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1]);
+ nextP[6][8] = P[6][8] + P[1][8]*SF[1] + P[3][8]*SF[0] + P[0][8]*SPP[0] - P[2][8]*SPP[1] + dt*(P[6][5] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1]);
+ nextP[6][9] = P[6][9] + P[1][9]*SF[1] + P[3][9]*SF[0] + P[0][9]*SPP[0] - P[2][9]*SPP[1] + dt*(P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1]);
+ nextP[6][10] = P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1];
+ nextP[6][11] = P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1];
+ nextP[6][12] = P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1];
+ nextP[6][13] = P[6][13] + P[1][13]*SF[1] + P[3][13]*SF[0] + P[0][13]*SPP[0] - P[2][13]*SPP[1];
+ nextP[6][14] = P[6][14] + P[1][14]*SF[1] + P[3][14]*SF[0] + P[0][14]*SPP[0] - P[2][14]*SPP[1];
+ nextP[6][15] = P[6][15] + P[1][15]*SF[1] + P[3][15]*SF[0] + P[0][15]*SPP[0] - P[2][15]*SPP[1];
+ nextP[6][16] = P[6][16] + P[1][16]*SF[1] + P[3][16]*SF[0] + P[0][16]*SPP[0] - P[2][16]*SPP[1];
+ nextP[6][17] = P[6][17] + P[1][17]*SF[1] + P[3][17]*SF[0] + P[0][17]*SPP[0] - P[2][17]*SPP[1];
+ nextP[6][18] = P[6][18] + P[1][18]*SF[1] + P[3][18]*SF[0] + P[0][18]*SPP[0] - P[2][18]*SPP[1];
+ nextP[6][19] = P[6][19] + P[1][19]*SF[1] + P[3][19]*SF[0] + P[0][19]*SPP[0] - P[2][19]*SPP[1];
+ nextP[6][20] = P[6][20] + P[1][20]*SF[1] + P[3][20]*SF[0] + P[0][20]*SPP[0] - P[2][20]*SPP[1];
+ nextP[7][0] = P[7][0] + P[4][0]*dt + SF[6]*(P[7][1] + P[4][1]*dt) + SPP[7]*(P[7][2] + P[4][2]*dt) + SPP[6]*(P[7][3] + P[4][3]*dt) + SPP[5]*(P[7][10] + P[4][10]*dt) + SPP[4]*(P[7][11] + P[4][11]*dt) + SPP[3]*(P[7][12] + P[4][12]*dt);
+ nextP[7][1] = P[7][1] + P[4][1]*dt + SF[5]*(P[7][0] + P[4][0]*dt) + SF[4]*(P[7][2] + P[4][2]*dt) + SPP[7]*(P[7][3] + P[4][3]*dt) + SPP[3]*(P[7][11] + P[4][11]*dt) - SPP[4]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][10] + P[4][10]*dt))/2;
+ nextP[7][2] = P[7][2] + P[4][2]*dt + SF[3]*(P[7][0] + P[4][0]*dt) + SF[5]*(P[7][3] + P[4][3]*dt) + SPP[6]*(P[7][1] + P[4][1]*dt) - SPP[3]*(P[7][10] + P[4][10]*dt) + SPP[5]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][11] + P[4][11]*dt))/2;
+ nextP[7][3] = P[7][3] + P[4][3]*dt + SF[4]*(P[7][0] + P[4][0]*dt) + SF[3]*(P[7][1] + P[4][1]*dt) + SF[6]*(P[7][2] + P[4][2]*dt) + SPP[4]*(P[7][10] + P[4][10]*dt) - SPP[5]*(P[7][11] + P[4][11]*dt) - (q0*(P[7][12] + P[4][12]*dt))/2;
+ nextP[7][4] = P[7][4] + P[4][4]*dt + SF[0]*(P[7][1] + P[4][1]*dt) + SF[2]*(P[7][0] + P[4][0]*dt) + SPP[0]*(P[7][2] + P[4][2]*dt) - SPP[2]*(P[7][3] + P[4][3]*dt);
+ nextP[7][5] = P[7][5] + P[4][5]*dt + SF[1]*(P[7][0] + P[4][0]*dt) + SF[0]*(P[7][2] + P[4][2]*dt) + SF[2]*(P[7][3] + P[4][3]*dt) - SPP[0]*(P[7][1] + P[4][1]*dt);
+ nextP[7][6] = P[7][6] + P[4][6]*dt + SF[1]*(P[7][1] + P[4][1]*dt) + SF[0]*(P[7][3] + P[4][3]*dt) + SPP[0]*(P[7][0] + P[4][0]*dt) - SPP[1]*(P[7][2] + P[4][2]*dt);
+ nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt);
+ nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt);
+ nextP[7][9] = P[7][9] + P[4][9]*dt + dt*(P[7][6] + P[4][6]*dt);
+ nextP[7][10] = P[7][10] + P[4][10]*dt;
+ nextP[7][11] = P[7][11] + P[4][11]*dt;
+ nextP[7][12] = P[7][12] + P[4][12]*dt;
+ nextP[7][13] = P[7][13] + P[4][13]*dt;
+ nextP[7][14] = P[7][14] + P[4][14]*dt;
+ nextP[7][15] = P[7][15] + P[4][15]*dt;
+ nextP[7][16] = P[7][16] + P[4][16]*dt;
+ nextP[7][17] = P[7][17] + P[4][17]*dt;
+ nextP[7][18] = P[7][18] + P[4][18]*dt;
+ nextP[7][19] = P[7][19] + P[4][19]*dt;
+ nextP[7][20] = P[7][20] + P[4][20]*dt;
+ nextP[8][0] = P[8][0] + P[5][0]*dt + SF[6]*(P[8][1] + P[5][1]*dt) + SPP[7]*(P[8][2] + P[5][2]*dt) + SPP[6]*(P[8][3] + P[5][3]*dt) + SPP[5]*(P[8][10] + P[5][10]*dt) + SPP[4]*(P[8][11] + P[5][11]*dt) + SPP[3]*(P[8][12] + P[5][12]*dt);
+ nextP[8][1] = P[8][1] + P[5][1]*dt + SF[5]*(P[8][0] + P[5][0]*dt) + SF[4]*(P[8][2] + P[5][2]*dt) + SPP[7]*(P[8][3] + P[5][3]*dt) + SPP[3]*(P[8][11] + P[5][11]*dt) - SPP[4]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][10] + P[5][10]*dt))/2;
+ nextP[8][2] = P[8][2] + P[5][2]*dt + SF[3]*(P[8][0] + P[5][0]*dt) + SF[5]*(P[8][3] + P[5][3]*dt) + SPP[6]*(P[8][1] + P[5][1]*dt) - SPP[3]*(P[8][10] + P[5][10]*dt) + SPP[5]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][11] + P[5][11]*dt))/2;
+ nextP[8][3] = P[8][3] + P[5][3]*dt + SF[4]*(P[8][0] + P[5][0]*dt) + SF[3]*(P[8][1] + P[5][1]*dt) + SF[6]*(P[8][2] + P[5][2]*dt) + SPP[4]*(P[8][10] + P[5][10]*dt) - SPP[5]*(P[8][11] + P[5][11]*dt) - (q0*(P[8][12] + P[5][12]*dt))/2;
+ nextP[8][4] = P[8][4] + P[5][4]*dt + SF[0]*(P[8][1] + P[5][1]*dt) + SF[2]*(P[8][0] + P[5][0]*dt) + SPP[0]*(P[8][2] + P[5][2]*dt) - SPP[2]*(P[8][3] + P[5][3]*dt);
+ nextP[8][5] = P[8][5] + P[5][5]*dt + SF[1]*(P[8][0] + P[5][0]*dt) + SF[0]*(P[8][2] + P[5][2]*dt) + SF[2]*(P[8][3] + P[5][3]*dt) - SPP[0]*(P[8][1] + P[5][1]*dt);
+ nextP[8][6] = P[8][6] + P[5][6]*dt + SF[1]*(P[8][1] + P[5][1]*dt) + SF[0]*(P[8][3] + P[5][3]*dt) + SPP[0]*(P[8][0] + P[5][0]*dt) - SPP[1]*(P[8][2] + P[5][2]*dt);
+ nextP[8][7] = P[8][7] + P[5][7]*dt + dt*(P[8][4] + P[5][4]*dt);
+ nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt);
+ nextP[8][9] = P[8][9] + P[5][9]*dt + dt*(P[8][6] + P[5][6]*dt);
+ nextP[8][10] = P[8][10] + P[5][10]*dt;
+ nextP[8][11] = P[8][11] + P[5][11]*dt;
+ nextP[8][12] = P[8][12] + P[5][12]*dt;
+ nextP[8][13] = P[8][13] + P[5][13]*dt;
+ nextP[8][14] = P[8][14] + P[5][14]*dt;
+ nextP[8][15] = P[8][15] + P[5][15]*dt;
+ nextP[8][16] = P[8][16] + P[5][16]*dt;
+ nextP[8][17] = P[8][17] + P[5][17]*dt;
+ nextP[8][18] = P[8][18] + P[5][18]*dt;
+ nextP[8][19] = P[8][19] + P[5][19]*dt;
+ nextP[8][20] = P[8][20] + P[5][20]*dt;
+ nextP[9][0] = P[9][0] + P[6][0]*dt + SF[6]*(P[9][1] + P[6][1]*dt) + SPP[7]*(P[9][2] + P[6][2]*dt) + SPP[6]*(P[9][3] + P[6][3]*dt) + SPP[5]*(P[9][10] + P[6][10]*dt) + SPP[4]*(P[9][11] + P[6][11]*dt) + SPP[3]*(P[9][12] + P[6][12]*dt);
+ nextP[9][1] = P[9][1] + P[6][1]*dt + SF[5]*(P[9][0] + P[6][0]*dt) + SF[4]*(P[9][2] + P[6][2]*dt) + SPP[7]*(P[9][3] + P[6][3]*dt) + SPP[3]*(P[9][11] + P[6][11]*dt) - SPP[4]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][10] + P[6][10]*dt))/2;
+ nextP[9][2] = P[9][2] + P[6][2]*dt + SF[3]*(P[9][0] + P[6][0]*dt) + SF[5]*(P[9][3] + P[6][3]*dt) + SPP[6]*(P[9][1] + P[6][1]*dt) - SPP[3]*(P[9][10] + P[6][10]*dt) + SPP[5]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][11] + P[6][11]*dt))/2;
+ nextP[9][3] = P[9][3] + P[6][3]*dt + SF[4]*(P[9][0] + P[6][0]*dt) + SF[3]*(P[9][1] + P[6][1]*dt) + SF[6]*(P[9][2] + P[6][2]*dt) + SPP[4]*(P[9][10] + P[6][10]*dt) - SPP[5]*(P[9][11] + P[6][11]*dt) - (q0*(P[9][12] + P[6][12]*dt))/2;
+ nextP[9][4] = P[9][4] + P[6][4]*dt + SF[0]*(P[9][1] + P[6][1]*dt) + SF[2]*(P[9][0] + P[6][0]*dt) + SPP[0]*(P[9][2] + P[6][2]*dt) - SPP[2]*(P[9][3] + P[6][3]*dt);
+ nextP[9][5] = P[9][5] + P[6][5]*dt + SF[1]*(P[9][0] + P[6][0]*dt) + SF[0]*(P[9][2] + P[6][2]*dt) + SF[2]*(P[9][3] + P[6][3]*dt) - SPP[0]*(P[9][1] + P[6][1]*dt);
+ nextP[9][6] = P[9][6] + P[6][6]*dt + SF[1]*(P[9][1] + P[6][1]*dt) + SF[0]*(P[9][3] + P[6][3]*dt) + SPP[0]*(P[9][0] + P[6][0]*dt) - SPP[1]*(P[9][2] + P[6][2]*dt);
+ nextP[9][7] = P[9][7] + P[6][7]*dt + dt*(P[9][4] + P[6][4]*dt);
+ nextP[9][8] = P[9][8] + P[6][8]*dt + dt*(P[9][5] + P[6][5]*dt);
+ nextP[9][9] = P[9][9] + P[6][9]*dt + dt*(P[9][6] + P[6][6]*dt);
+ nextP[9][10] = P[9][10] + P[6][10]*dt;
+ nextP[9][11] = P[9][11] + P[6][11]*dt;
+ nextP[9][12] = P[9][12] + P[6][12]*dt;
+ nextP[9][13] = P[9][13] + P[6][13]*dt;
+ nextP[9][14] = P[9][14] + P[6][14]*dt;
+ nextP[9][15] = P[9][15] + P[6][15]*dt;
+ nextP[9][16] = P[9][16] + P[6][16]*dt;
+ nextP[9][17] = P[9][17] + P[6][17]*dt;
+ nextP[9][18] = P[9][18] + P[6][18]*dt;
+ nextP[9][19] = P[9][19] + P[6][19]*dt;
+ nextP[9][20] = P[9][20] + P[6][20]*dt;
+ nextP[10][0] = P[10][0] + P[10][1]*SF[6] + P[10][2]*SPP[7] + P[10][3]*SPP[6] + P[10][10]*SPP[5] + P[10][11]*SPP[4] + P[10][12]*SPP[3];
+ nextP[10][1] = P[10][1] + P[10][0]*SF[5] + P[10][2]*SF[4] + P[10][3]*SPP[7] + P[10][11]*SPP[3] - P[10][12]*SPP[4] - (P[10][10]*q0)/2;
+ nextP[10][2] = P[10][2] + P[10][0]*SF[3] + P[10][3]*SF[5] + P[10][1]*SPP[6] - P[10][10]*SPP[3] + P[10][12]*SPP[5] - (P[10][11]*q0)/2;
+ nextP[10][3] = P[10][3] + P[10][0]*SF[4] + P[10][1]*SF[3] + P[10][2]*SF[6] + P[10][10]*SPP[4] - P[10][11]*SPP[5] - (P[10][12]*q0)/2;
+ nextP[10][4] = P[10][4] + P[10][1]*SF[0] + P[10][0]*SF[2] + P[10][2]*SPP[0] - P[10][3]*SPP[2];
+ nextP[10][5] = P[10][5] + P[10][0]*SF[1] + P[10][2]*SF[0] + P[10][3]*SF[2] - P[10][1]*SPP[0];
+ nextP[10][6] = P[10][6] + P[10][1]*SF[1] + P[10][3]*SF[0] + P[10][0]*SPP[0] - P[10][2]*SPP[1];
+ nextP[10][7] = P[10][7] + P[10][4]*dt;
+ nextP[10][8] = P[10][8] + P[10][5]*dt;
+ nextP[10][9] = P[10][9] + P[10][6]*dt;
+ nextP[10][10] = P[10][10];
+ nextP[10][11] = P[10][11];
+ nextP[10][12] = P[10][12];
+ nextP[10][13] = P[10][13];
+ nextP[10][14] = P[10][14];
+ nextP[10][15] = P[10][15];
+ nextP[10][16] = P[10][16];
+ nextP[10][17] = P[10][17];
+ nextP[10][18] = P[10][18];
+ nextP[10][19] = P[10][19];
+ nextP[10][20] = P[10][20];
+ nextP[11][0] = P[11][0] + P[11][1]*SF[6] + P[11][2]*SPP[7] + P[11][3]*SPP[6] + P[11][10]*SPP[5] + P[11][11]*SPP[4] + P[11][12]*SPP[3];
+ nextP[11][1] = P[11][1] + P[11][0]*SF[5] + P[11][2]*SF[4] + P[11][3]*SPP[7] + P[11][11]*SPP[3] - P[11][12]*SPP[4] - (P[11][10]*q0)/2;
+ nextP[11][2] = P[11][2] + P[11][0]*SF[3] + P[11][3]*SF[5] + P[11][1]*SPP[6] - P[11][10]*SPP[3] + P[11][12]*SPP[5] - (P[11][11]*q0)/2;
+ nextP[11][3] = P[11][3] + P[11][0]*SF[4] + P[11][1]*SF[3] + P[11][2]*SF[6] + P[11][10]*SPP[4] - P[11][11]*SPP[5] - (P[11][12]*q0)/2;
+ nextP[11][4] = P[11][4] + P[11][1]*SF[0] + P[11][0]*SF[2] + P[11][2]*SPP[0] - P[11][3]*SPP[2];
+ nextP[11][5] = P[11][5] + P[11][0]*SF[1] + P[11][2]*SF[0] + P[11][3]*SF[2] - P[11][1]*SPP[0];
+ nextP[11][6] = P[11][6] + P[11][1]*SF[1] + P[11][3]*SF[0] + P[11][0]*SPP[0] - P[11][2]*SPP[1];
+ nextP[11][7] = P[11][7] + P[11][4]*dt;
+ nextP[11][8] = P[11][8] + P[11][5]*dt;
+ nextP[11][9] = P[11][9] + P[11][6]*dt;
+ nextP[11][10] = P[11][10];
+ nextP[11][11] = P[11][11];
+ nextP[11][12] = P[11][12];
+ nextP[11][13] = P[11][13];
+ nextP[11][14] = P[11][14];
+ nextP[11][15] = P[11][15];
+ nextP[11][16] = P[11][16];
+ nextP[11][17] = P[11][17];
+ nextP[11][18] = P[11][18];
+ nextP[11][19] = P[11][19];
+ nextP[11][20] = P[11][20];
+ nextP[12][0] = P[12][0] + P[12][1]*SF[6] + P[12][2]*SPP[7] + P[12][3]*SPP[6] + P[12][10]*SPP[5] + P[12][11]*SPP[4] + P[12][12]*SPP[3];
+ nextP[12][1] = P[12][1] + P[12][0]*SF[5] + P[12][2]*SF[4] + P[12][3]*SPP[7] + P[12][11]*SPP[3] - P[12][12]*SPP[4] - (P[12][10]*q0)/2;
+ nextP[12][2] = P[12][2] + P[12][0]*SF[3] + P[12][3]*SF[5] + P[12][1]*SPP[6] - P[12][10]*SPP[3] + P[12][12]*SPP[5] - (P[12][11]*q0)/2;
+ nextP[12][3] = P[12][3] + P[12][0]*SF[4] + P[12][1]*SF[3] + P[12][2]*SF[6] + P[12][10]*SPP[4] - P[12][11]*SPP[5] - (P[12][12]*q0)/2;
+ nextP[12][4] = P[12][4] + P[12][1]*SF[0] + P[12][0]*SF[2] + P[12][2]*SPP[0] - P[12][3]*SPP[2];
+ nextP[12][5] = P[12][5] + P[12][0]*SF[1] + P[12][2]*SF[0] + P[12][3]*SF[2] - P[12][1]*SPP[0];
+ nextP[12][6] = P[12][6] + P[12][1]*SF[1] + P[12][3]*SF[0] + P[12][0]*SPP[0] - P[12][2]*SPP[1];
+ nextP[12][7] = P[12][7] + P[12][4]*dt;
+ nextP[12][8] = P[12][8] + P[12][5]*dt;
+ nextP[12][9] = P[12][9] + P[12][6]*dt;
+ nextP[12][10] = P[12][10];
+ nextP[12][11] = P[12][11];
+ nextP[12][12] = P[12][12];
+ nextP[12][13] = P[12][13];
+ nextP[12][14] = P[12][14];
+ nextP[12][15] = P[12][15];
+ nextP[12][16] = P[12][16];
+ nextP[12][17] = P[12][17];
+ nextP[12][18] = P[12][18];
+ nextP[12][19] = P[12][19];
+ nextP[12][20] = P[12][20];
+ nextP[13][0] = P[13][0] + P[13][1]*SF[6] + P[13][2]*SPP[7] + P[13][3]*SPP[6] + P[13][10]*SPP[5] + P[13][11]*SPP[4] + P[13][12]*SPP[3];
+ nextP[13][1] = P[13][1] + P[13][0]*SF[5] + P[13][2]*SF[4] + P[13][3]*SPP[7] + P[13][11]*SPP[3] - P[13][12]*SPP[4] - (P[13][10]*q0)/2;
+ nextP[13][2] = P[13][2] + P[13][0]*SF[3] + P[13][3]*SF[5] + P[13][1]*SPP[6] - P[13][10]*SPP[3] + P[13][12]*SPP[5] - (P[13][11]*q0)/2;
+ nextP[13][3] = P[13][3] + P[13][0]*SF[4] + P[13][1]*SF[3] + P[13][2]*SF[6] + P[13][10]*SPP[4] - P[13][11]*SPP[5] - (P[13][12]*q0)/2;
+ nextP[13][4] = P[13][4] + P[13][1]*SF[0] + P[13][0]*SF[2] + P[13][2]*SPP[0] - P[13][3]*SPP[2];
+ nextP[13][5] = P[13][5] + P[13][0]*SF[1] + P[13][2]*SF[0] + P[13][3]*SF[2] - P[13][1]*SPP[0];
+ nextP[13][6] = P[13][6] + P[13][1]*SF[1] + P[13][3]*SF[0] + P[13][0]*SPP[0] - P[13][2]*SPP[1];
+ nextP[13][7] = P[13][7] + P[13][4]*dt;
+ nextP[13][8] = P[13][8] + P[13][5]*dt;
+ nextP[13][9] = P[13][9] + P[13][6]*dt;
+ nextP[13][10] = P[13][10];
+ nextP[13][11] = P[13][11];
+ nextP[13][12] = P[13][12];
+ nextP[13][13] = P[13][13];
+ nextP[13][14] = P[13][14];
+ nextP[13][15] = P[13][15];
+ nextP[13][16] = P[13][16];
+ nextP[13][17] = P[13][17];
+ nextP[13][18] = P[13][18];
+ nextP[13][19] = P[13][19];
+ nextP[13][20] = P[13][20];
+ nextP[14][0] = P[14][0] + P[14][1]*SF[6] + P[14][2]*SPP[7] + P[14][3]*SPP[6] + P[14][10]*SPP[5] + P[14][11]*SPP[4] + P[14][12]*SPP[3];
+ nextP[14][1] = P[14][1] + P[14][0]*SF[5] + P[14][2]*SF[4] + P[14][3]*SPP[7] + P[14][11]*SPP[3] - P[14][12]*SPP[4] - (P[14][10]*q0)/2;
+ nextP[14][2] = P[14][2] + P[14][0]*SF[3] + P[14][3]*SF[5] + P[14][1]*SPP[6] - P[14][10]*SPP[3] + P[14][12]*SPP[5] - (P[14][11]*q0)/2;
+ nextP[14][3] = P[14][3] + P[14][0]*SF[4] + P[14][1]*SF[3] + P[14][2]*SF[6] + P[14][10]*SPP[4] - P[14][11]*SPP[5] - (P[14][12]*q0)/2;
+ nextP[14][4] = P[14][4] + P[14][1]*SF[0] + P[14][0]*SF[2] + P[14][2]*SPP[0] - P[14][3]*SPP[2];
+ nextP[14][5] = P[14][5] + P[14][0]*SF[1] + P[14][2]*SF[0] + P[14][3]*SF[2] - P[14][1]*SPP[0];
+ nextP[14][6] = P[14][6] + P[14][1]*SF[1] + P[14][3]*SF[0] + P[14][0]*SPP[0] - P[14][2]*SPP[1];
+ nextP[14][7] = P[14][7] + P[14][4]*dt;
+ nextP[14][8] = P[14][8] + P[14][5]*dt;
+ nextP[14][9] = P[14][9] + P[14][6]*dt;
+ nextP[14][10] = P[14][10];
+ nextP[14][11] = P[14][11];
+ nextP[14][12] = P[14][12];
+ nextP[14][13] = P[14][13];
+ nextP[14][14] = P[14][14];
+ nextP[14][15] = P[14][15];
+ nextP[14][16] = P[14][16];
+ nextP[14][17] = P[14][17];
+ nextP[14][18] = P[14][18];
+ nextP[14][19] = P[14][19];
+ nextP[14][20] = P[14][20];
+ nextP[15][0] = P[15][0] + P[15][1]*SF[6] + P[15][2]*SPP[7] + P[15][3]*SPP[6] + P[15][10]*SPP[5] + P[15][11]*SPP[4] + P[15][12]*SPP[3];
+ nextP[15][1] = P[15][1] + P[15][0]*SF[5] + P[15][2]*SF[4] + P[15][3]*SPP[7] + P[15][11]*SPP[3] - P[15][12]*SPP[4] - (P[15][10]*q0)/2;
+ nextP[15][2] = P[15][2] + P[15][0]*SF[3] + P[15][3]*SF[5] + P[15][1]*SPP[6] - P[15][10]*SPP[3] + P[15][12]*SPP[5] - (P[15][11]*q0)/2;
+ nextP[15][3] = P[15][3] + P[15][0]*SF[4] + P[15][1]*SF[3] + P[15][2]*SF[6] + P[15][10]*SPP[4] - P[15][11]*SPP[5] - (P[15][12]*q0)/2;
+ nextP[15][4] = P[15][4] + P[15][1]*SF[0] + P[15][0]*SF[2] + P[15][2]*SPP[0] - P[15][3]*SPP[2];
+ nextP[15][5] = P[15][5] + P[15][0]*SF[1] + P[15][2]*SF[0] + P[15][3]*SF[2] - P[15][1]*SPP[0];
+ nextP[15][6] = P[15][6] + P[15][1]*SF[1] + P[15][3]*SF[0] + P[15][0]*SPP[0] - P[15][2]*SPP[1];
+ nextP[15][7] = P[15][7] + P[15][4]*dt;
+ nextP[15][8] = P[15][8] + P[15][5]*dt;
+ nextP[15][9] = P[15][9] + P[15][6]*dt;
+ nextP[15][10] = P[15][10];
+ nextP[15][11] = P[15][11];
+ nextP[15][12] = P[15][12];
+ nextP[15][13] = P[15][13];
+ nextP[15][14] = P[15][14];
+ nextP[15][15] = P[15][15];
+ nextP[15][16] = P[15][16];
+ nextP[15][17] = P[15][17];
+ nextP[15][18] = P[15][18];
+ nextP[15][19] = P[15][19];
+ nextP[15][20] = P[15][20];
+ nextP[16][0] = P[16][0] + P[16][1]*SF[6] + P[16][2]*SPP[7] + P[16][3]*SPP[6] + P[16][10]*SPP[5] + P[16][11]*SPP[4] + P[16][12]*SPP[3];
+ nextP[16][1] = P[16][1] + P[16][0]*SF[5] + P[16][2]*SF[4] + P[16][3]*SPP[7] + P[16][11]*SPP[3] - P[16][12]*SPP[4] - (P[16][10]*q0)/2;
+ nextP[16][2] = P[16][2] + P[16][0]*SF[3] + P[16][3]*SF[5] + P[16][1]*SPP[6] - P[16][10]*SPP[3] + P[16][12]*SPP[5] - (P[16][11]*q0)/2;
+ nextP[16][3] = P[16][3] + P[16][0]*SF[4] + P[16][1]*SF[3] + P[16][2]*SF[6] + P[16][10]*SPP[4] - P[16][11]*SPP[5] - (P[16][12]*q0)/2;
+ nextP[16][4] = P[16][4] + P[16][1]*SF[0] + P[16][0]*SF[2] + P[16][2]*SPP[0] - P[16][3]*SPP[2];
+ nextP[16][5] = P[16][5] + P[16][0]*SF[1] + P[16][2]*SF[0] + P[16][3]*SF[2] - P[16][1]*SPP[0];
+ nextP[16][6] = P[16][6] + P[16][1]*SF[1] + P[16][3]*SF[0] + P[16][0]*SPP[0] - P[16][2]*SPP[1];
+ nextP[16][7] = P[16][7] + P[16][4]*dt;
+ nextP[16][8] = P[16][8] + P[16][5]*dt;
+ nextP[16][9] = P[16][9] + P[16][6]*dt;
+ nextP[16][10] = P[16][10];
+ nextP[16][11] = P[16][11];
+ nextP[16][12] = P[16][12];
+ nextP[16][13] = P[16][13];
+ nextP[16][14] = P[16][14];
+ nextP[16][15] = P[16][15];
+ nextP[16][16] = P[16][16];
+ nextP[16][17] = P[16][17];
+ nextP[16][18] = P[16][18];
+ nextP[16][19] = P[16][19];
+ nextP[16][20] = P[16][20];
+ nextP[17][0] = P[17][0] + P[17][1]*SF[6] + P[17][2]*SPP[7] + P[17][3]*SPP[6] + P[17][10]*SPP[5] + P[17][11]*SPP[4] + P[17][12]*SPP[3];
+ nextP[17][1] = P[17][1] + P[17][0]*SF[5] + P[17][2]*SF[4] + P[17][3]*SPP[7] + P[17][11]*SPP[3] - P[17][12]*SPP[4] - (P[17][10]*q0)/2;
+ nextP[17][2] = P[17][2] + P[17][0]*SF[3] + P[17][3]*SF[5] + P[17][1]*SPP[6] - P[17][10]*SPP[3] + P[17][12]*SPP[5] - (P[17][11]*q0)/2;
+ nextP[17][3] = P[17][3] + P[17][0]*SF[4] + P[17][1]*SF[3] + P[17][2]*SF[6] + P[17][10]*SPP[4] - P[17][11]*SPP[5] - (P[17][12]*q0)/2;
+ nextP[17][4] = P[17][4] + P[17][1]*SF[0] + P[17][0]*SF[2] + P[17][2]*SPP[0] - P[17][3]*SPP[2];
+ nextP[17][5] = P[17][5] + P[17][0]*SF[1] + P[17][2]*SF[0] + P[17][3]*SF[2] - P[17][1]*SPP[0];
+ nextP[17][6] = P[17][6] + P[17][1]*SF[1] + P[17][3]*SF[0] + P[17][0]*SPP[0] - P[17][2]*SPP[1];
+ nextP[17][7] = P[17][7] + P[17][4]*dt;
+ nextP[17][8] = P[17][8] + P[17][5]*dt;
+ nextP[17][9] = P[17][9] + P[17][6]*dt;
+ nextP[17][10] = P[17][10];
+ nextP[17][11] = P[17][11];
+ nextP[17][12] = P[17][12];
+ nextP[17][13] = P[17][13];
+ nextP[17][14] = P[17][14];
+ nextP[17][15] = P[17][15];
+ nextP[17][16] = P[17][16];
+ nextP[17][17] = P[17][17];
+ nextP[17][18] = P[17][18];
+ nextP[17][19] = P[17][19];
+ nextP[17][20] = P[17][20];
+ nextP[18][0] = P[18][0] + P[18][1]*SF[6] + P[18][2]*SPP[7] + P[18][3]*SPP[6] + P[18][10]*SPP[5] + P[18][11]*SPP[4] + P[18][12]*SPP[3];
+ nextP[18][1] = P[18][1] + P[18][0]*SF[5] + P[18][2]*SF[4] + P[18][3]*SPP[7] + P[18][11]*SPP[3] - P[18][12]*SPP[4] - (P[18][10]*q0)/2;
+ nextP[18][2] = P[18][2] + P[18][0]*SF[3] + P[18][3]*SF[5] + P[18][1]*SPP[6] - P[18][10]*SPP[3] + P[18][12]*SPP[5] - (P[18][11]*q0)/2;
+ nextP[18][3] = P[18][3] + P[18][0]*SF[4] + P[18][1]*SF[3] + P[18][2]*SF[6] + P[18][10]*SPP[4] - P[18][11]*SPP[5] - (P[18][12]*q0)/2;
+ nextP[18][4] = P[18][4] + P[18][1]*SF[0] + P[18][0]*SF[2] + P[18][2]*SPP[0] - P[18][3]*SPP[2];
+ nextP[18][5] = P[18][5] + P[18][0]*SF[1] + P[18][2]*SF[0] + P[18][3]*SF[2] - P[18][1]*SPP[0];
+ nextP[18][6] = P[18][6] + P[18][1]*SF[1] + P[18][3]*SF[0] + P[18][0]*SPP[0] - P[18][2]*SPP[1];
+ nextP[18][7] = P[18][7] + P[18][4]*dt;
+ nextP[18][8] = P[18][8] + P[18][5]*dt;
+ nextP[18][9] = P[18][9] + P[18][6]*dt;
+ nextP[18][10] = P[18][10];
+ nextP[18][11] = P[18][11];
+ nextP[18][12] = P[18][12];
+ nextP[18][13] = P[18][13];
+ nextP[18][14] = P[18][14];
+ nextP[18][15] = P[18][15];
+ nextP[18][16] = P[18][16];
+ nextP[18][17] = P[18][17];
+ nextP[18][18] = P[18][18];
+ nextP[18][19] = P[18][19];
+ nextP[18][20] = P[18][20];
+ nextP[19][0] = P[19][0] + P[19][1]*SF[6] + P[19][2]*SPP[7] + P[19][3]*SPP[6] + P[19][10]*SPP[5] + P[19][11]*SPP[4] + P[19][12]*SPP[3];
+ nextP[19][1] = P[19][1] + P[19][0]*SF[5] + P[19][2]*SF[4] + P[19][3]*SPP[7] + P[19][11]*SPP[3] - P[19][12]*SPP[4] - (P[19][10]*q0)/2;
+ nextP[19][2] = P[19][2] + P[19][0]*SF[3] + P[19][3]*SF[5] + P[19][1]*SPP[6] - P[19][10]*SPP[3] + P[19][12]*SPP[5] - (P[19][11]*q0)/2;
+ nextP[19][3] = P[19][3] + P[19][0]*SF[4] + P[19][1]*SF[3] + P[19][2]*SF[6] + P[19][10]*SPP[4] - P[19][11]*SPP[5] - (P[19][12]*q0)/2;
+ nextP[19][4] = P[19][4] + P[19][1]*SF[0] + P[19][0]*SF[2] + P[19][2]*SPP[0] - P[19][3]*SPP[2];
+ nextP[19][5] = P[19][5] + P[19][0]*SF[1] + P[19][2]*SF[0] + P[19][3]*SF[2] - P[19][1]*SPP[0];
+ nextP[19][6] = P[19][6] + P[19][1]*SF[1] + P[19][3]*SF[0] + P[19][0]*SPP[0] - P[19][2]*SPP[1];
+ nextP[19][7] = P[19][7] + P[19][4]*dt;
+ nextP[19][8] = P[19][8] + P[19][5]*dt;
+ nextP[19][9] = P[19][9] + P[19][6]*dt;
+ nextP[19][10] = P[19][10];
+ nextP[19][11] = P[19][11];
+ nextP[19][12] = P[19][12];
+ nextP[19][13] = P[19][13];
+ nextP[19][14] = P[19][14];
+ nextP[19][15] = P[19][15];
+ nextP[19][16] = P[19][16];
+ nextP[19][17] = P[19][17];
+ nextP[19][18] = P[19][18];
+ nextP[19][19] = P[19][19];
+ nextP[19][20] = P[19][20];
+ nextP[20][0] = P[20][0] + P[20][1]*SF[6] + P[20][2]*SPP[7] + P[20][3]*SPP[6] + P[20][10]*SPP[5] + P[20][11]*SPP[4] + P[20][12]*SPP[3];
+ nextP[20][1] = P[20][1] + P[20][0]*SF[5] + P[20][2]*SF[4] + P[20][3]*SPP[7] + P[20][11]*SPP[3] - P[20][12]*SPP[4] - (P[20][10]*q0)/2;
+ nextP[20][2] = P[20][2] + P[20][0]*SF[3] + P[20][3]*SF[5] + P[20][1]*SPP[6] - P[20][10]*SPP[3] + P[20][12]*SPP[5] - (P[20][11]*q0)/2;
+ nextP[20][3] = P[20][3] + P[20][0]*SF[4] + P[20][1]*SF[3] + P[20][2]*SF[6] + P[20][10]*SPP[4] - P[20][11]*SPP[5] - (P[20][12]*q0)/2;
+ nextP[20][4] = P[20][4] + P[20][1]*SF[0] + P[20][0]*SF[2] + P[20][2]*SPP[0] - P[20][3]*SPP[2];
+ nextP[20][5] = P[20][5] + P[20][0]*SF[1] + P[20][2]*SF[0] + P[20][3]*SF[2] - P[20][1]*SPP[0];
+ nextP[20][6] = P[20][6] + P[20][1]*SF[1] + P[20][3]*SF[0] + P[20][0]*SPP[0] - P[20][2]*SPP[1];
+ nextP[20][7] = P[20][7] + P[20][4]*dt;
+ nextP[20][8] = P[20][8] + P[20][5]*dt;
+ nextP[20][9] = P[20][9] + P[20][6]*dt;
+ nextP[20][10] = P[20][10];
+ nextP[20][11] = P[20][11];
+ nextP[20][12] = P[20][12];
+ nextP[20][13] = P[20][13];
+ nextP[20][14] = P[20][14];
+ nextP[20][15] = P[20][15];
+ nextP[20][16] = P[20][16];
+ nextP[20][17] = P[20][17];
+ nextP[20][18] = P[20][18];
+ nextP[20][19] = P[20][19];
+ nextP[20][20] = P[20][20];
+
+ for (unsigned i = 0; i < n_states; i++)
+ {
+ nextP[i][i] = nextP[i][i] + processNoise[i];
+ }
+
+ // If on ground or no magnetometer fitted, inhibit magnetometer bias updates by
+ // setting the coresponding covariance terms to zero.
+ if (onGround || !useCompass)
+ {
+ zeroRows(nextP,15,20);
+ zeroCols(nextP,15,20);
+ }
+
+ // If on ground or not using airspeed sensing, inhibit wind velocity
+ // covariance growth.
+ if (onGround || !useAirspeed)
+ {
+ zeroRows(nextP,13,14);
+ zeroCols(nextP,13,14);
+ }
+
+ // If the total position variance exceds 1E6 (1000m), then stop covariance
+ // growth by setting the predicted to the previous values
+ // This prevent an ill conditioned matrix from occurring for long periods
+ // without GPS
+ if ((P[7][7] + P[8][8]) > 1E6f)
+ {
+ for (uint8_t i=7; i<=8; i++)
+ {
+ for (unsigned j = 0; j < n_states; j++)
+ {
+ nextP[i][j] = P[i][j];
+ nextP[j][i] = P[j][i];
+ }
+ }
+ }
+
+ if (onGround || staticMode) {
+ // copy the portion of the variances we want to
+ // propagate
+ for (unsigned i = 0; i < 14; i++) {
+ P[i][i] = nextP[i][i];
+
+ // force symmetry for observable states
+ // force zero for non-observable states
+ for (unsigned i = 1; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < i; j++)
+ {
+ if ((i > 12) || (j > 12)) {
+ P[i][j] = 0.0f;
+ } else {
+ P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
+ }
+ P[j][i] = P[i][j];
+ }
+ }
+ }
+
+ } else {
+
+ // Copy covariance
+ for (unsigned i = 0; i < n_states; i++) {
+ P[i][i] = nextP[i][i];
+ }
+
+ // force symmetry for observable states
+ for (unsigned i = 1; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < i; j++)
+ {
+ P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
+ P[j][i] = P[i][j];
+ }
+ }
+
+ }
+
+ ConstrainVariances();
+}
+
+void AttPosEKF::FuseVelposNED()
+{
+
+// declare variables used by fault isolation logic
+ uint32_t gpsRetryTime = 30000; // time in msec before GPS fusion will be retried following innovation consistency failure
+ uint32_t gpsRetryTimeNoTAS = 5000; // retry time if no TAS measurement available
+ uint32_t hgtRetryTime = 5000; // height measurement retry time
+ uint32_t horizRetryTime;
+
+// declare variables used to check measurement errors
+ float velInnov[3] = {0.0f,0.0f,0.0f};
+ float posInnov[2] = {0.0f,0.0f};
+ float hgtInnov = 0.0f;
+
+// declare variables used to control access to arrays
+ bool fuseData[6] = {false,false,false,false,false,false};
+ uint8_t stateIndex;
+ uint8_t obsIndex;
+ uint8_t indexLimit;
+
+// declare variables used by state and covariance update calculations
+ float velErr;
+ float posErr;
+ float R_OBS[6];
+ float observation[6];
+ float SK;
+ float quatMag;
+
+// Perform sequential fusion of GPS measurements. This assumes that the
+// errors in the different velocity and position components are
+// uncorrelated which is not true, however in the absence of covariance
+// data from the GPS receiver it is the only assumption we can make
+// so we might as well take advantage of the computational efficiencies
+// associated with sequential fusion
+ if (fuseVelData || fusePosData || fuseHgtData)
+ {
+ // set the GPS data timeout depending on whether airspeed data is present
+ if (useAirspeed) horizRetryTime = gpsRetryTime;
+ else horizRetryTime = gpsRetryTimeNoTAS;
+
+ // Form the observation vector
+ for (uint8_t i=0; i<=2; i++) observation[i] = velNED[i];
+ for (uint8_t i=3; i<=4; i++) observation[i] = posNE[i-3];
+ observation[5] = -(hgtMea);
+
+ // Estimate the GPS Velocity, GPS horiz position and height measurement variances.
+ velErr = 0.2f*accNavMag; // additional error in GPS velocities caused by manoeuvring
+ posErr = 0.2f*accNavMag; // additional error in GPS position caused by manoeuvring
+ R_OBS[0] = 0.04f + sq(velErr);
+ R_OBS[1] = R_OBS[0];
+ R_OBS[2] = 0.08f + sq(velErr);
+ R_OBS[3] = R_OBS[2];
+ R_OBS[4] = 4.0f + sq(posErr);
+ R_OBS[5] = 4.0f;
+
+ // Set innovation variances to zero default
+ for (uint8_t i = 0; i<=5; i++)
+ {
+ varInnovVelPos[i] = 0.0f;
+ }
+ // calculate innovations and check GPS data validity using an innovation consistency check
+ if (fuseVelData)
+ {
+ // test velocity measurements
+ uint8_t imax = 2;
+ if (fusionModeGPS == 1) imax = 1;
+ for (uint8_t i = 0; i<=imax; i++)
+ {
+ velInnov[i] = statesAtVelTime[i+4] - velNED[i];
+ stateIndex = 4 + i;
+ varInnovVelPos[i] = P[stateIndex][stateIndex] + R_OBS[i];
+ }
+ // apply a 5-sigma threshold
+ current_ekf_state.velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0f * (varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]);
+ current_ekf_state.velTimeout = (millis() - current_ekf_state.velFailTime) > horizRetryTime;
+ if (current_ekf_state.velHealth || current_ekf_state.velTimeout)
+ {
+ current_ekf_state.velHealth = true;
+ current_ekf_state.velFailTime = millis();
+ }
+ else
+ {
+ current_ekf_state.velHealth = false;
+ }
+ }
+ if (fusePosData)
+ {
+ // test horizontal position measurements
+ posInnov[0] = statesAtPosTime[7] - posNE[0];
+ posInnov[1] = statesAtPosTime[8] - posNE[1];
+ varInnovVelPos[3] = P[7][7] + R_OBS[3];
+ varInnovVelPos[4] = P[8][8] + R_OBS[4];
+ // apply a 10-sigma threshold
+ current_ekf_state.posHealth = (sq(posInnov[0]) + sq(posInnov[1])) < 100.0f*(varInnovVelPos[3] + varInnovVelPos[4]);
+ current_ekf_state.posTimeout = (millis() - current_ekf_state.posFailTime) > horizRetryTime;
+ if (current_ekf_state.posHealth || current_ekf_state.posTimeout)
+ {
+ current_ekf_state.posHealth = true;
+ current_ekf_state.posFailTime = millis();
+ }
+ else
+ {
+ current_ekf_state.posHealth = false;
+ }
+ }
+ // test height measurements
+ if (fuseHgtData)
+ {
+ hgtInnov = statesAtHgtTime[9] + hgtMea;
+ varInnovVelPos[5] = P[9][9] + R_OBS[5];
+ // apply a 10-sigma threshold
+ current_ekf_state.hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5];
+ current_ekf_state.hgtTimeout = (millis() - current_ekf_state.hgtFailTime) > hgtRetryTime;
+ if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout)
+ {
+ current_ekf_state.hgtHealth = true;
+ current_ekf_state.hgtFailTime = millis();
+ }
+ else
+ {
+ current_ekf_state.hgtHealth = false;
+ }
+ }
+ // Set range for sequential fusion of velocity and position measurements depending
+ // on which data is available and its health
+ if (fuseVelData && fusionModeGPS == 0 && current_ekf_state.velHealth)
+ {
+ fuseData[0] = true;
+ fuseData[1] = true;
+ fuseData[2] = true;
+ }
+ if (fuseVelData && fusionModeGPS == 1 && current_ekf_state.velHealth)
+ {
+ fuseData[0] = true;
+ fuseData[1] = true;
+ }
+ if (fusePosData && fusionModeGPS <= 2 && current_ekf_state.posHealth)
+ {
+ fuseData[3] = true;
+ fuseData[4] = true;
+ }
+ if (fuseHgtData && current_ekf_state.hgtHealth)
+ {
+ fuseData[5] = true;
+ }
+ // Limit range of states modified when on ground
+ if(!onGround)
+ {
+ indexLimit = 20;
+ }
+ else
+ {
+ indexLimit = 12;
+ }
+ // Fuse measurements sequentially
+ for (obsIndex=0; obsIndex<=5; obsIndex++)
+ {
+ if (fuseData[obsIndex])
+ {
+ stateIndex = 4 + obsIndex;
+ // Calculate the measurement innovation, using states from a
+ // different time coordinate if fusing height data
+ if (obsIndex >= 0 && obsIndex <= 2)
+ {
+ innovVelPos[obsIndex] = statesAtVelTime[stateIndex] - observation[obsIndex];
+ }
+ else if (obsIndex == 3 || obsIndex == 4)
+ {
+ innovVelPos[obsIndex] = statesAtPosTime[stateIndex] - observation[obsIndex];
+ }
+ else if (obsIndex == 5)
+ {
+ innovVelPos[obsIndex] = statesAtHgtTime[stateIndex] - observation[obsIndex];
+ }
+ // Calculate the Kalman Gain
+ // Calculate innovation variances - also used for data logging
+ varInnovVelPos[obsIndex] = P[stateIndex][stateIndex] + R_OBS[obsIndex];
+ SK = 1.0/varInnovVelPos[obsIndex];
+ for (uint8_t i= 0; i<=indexLimit; i++)
+ {
+ Kfusion[i] = P[i][stateIndex]*SK;
+ }
+ // Calculate state corrections and re-normalise the quaternions
+ for (uint8_t i = 0; i<=indexLimit; i++)
+ {
+ states[i] = states[i] - Kfusion[i] * innovVelPos[obsIndex];
+ }
+ quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12f) // divide by 0 protection
+ {
+ for (uint8_t i = 0; i<=3; i++)
+ {
+ states[i] = states[i] / quatMag;
+ }
+ }
+ // Update the covariance - take advantage of direct observation of a
+ // single state at index = stateIndex to reduce computations
+ // Optimised implementation of standard equation P = (I - K*H)*P;
+ for (uint8_t i= 0; i<=indexLimit; i++)
+ {
+ for (uint8_t j= 0; j<=indexLimit; j++)
+ {
+ KHP[i][j] = Kfusion[i] * P[stateIndex][j];
+ }
+ }
+ for (uint8_t i= 0; i<=indexLimit; i++)
+ {
+ for (uint8_t j= 0; j<=indexLimit; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
+ }
+ }
+
+ ForceSymmetry();
+ ConstrainVariances();
+
+ //printf("velh: %s, posh: %s, hgth: %s\n", ((velHealth) ? "OK" : "FAIL"), ((posHealth) ? "OK" : "FAIL"), ((hgtHealth) ? "OK" : "FAIL"));
+}
+
+void AttPosEKF::FuseMagnetometer()
+{
+ uint8_t obsIndex;
+ uint8_t indexLimit;
+ float DCM[3][3] =
+ {
+ {1.0f,0.0f,0.0f} ,
+ {0.0f,1.0f,0.0f} ,
+ {0.0f,0.0f,1.0f}
+ };
+ float MagPred[3] = {0.0f,0.0f,0.0f};
+ float SK_MX[6];
+ float SK_MY[5];
+ float SK_MZ[6];
+ float SH_MAG[9] = {0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f};
+
+// Perform sequential fusion of Magnetometer measurements.
+// This assumes that the errors in the different components are
+// uncorrelated which is not true, however in the absence of covariance
+// data fit is the only assumption we can make
+// so we might as well take advantage of the computational efficiencies
+// associated with sequential fusion
+ if (useCompass && (fuseMagData || obsIndex == 1 || obsIndex == 2))
+ {
+ // Limit range of states modified when on ground
+ if(!onGround)
+ {
+ indexLimit = 20;
+ }
+ else
+ {
+ indexLimit = 12;
+ }
+
+ static float q0 = 0.0f;
+ static float q1 = 0.0f;
+ static float q2 = 0.0f;
+ static float q3 = 1.0f;
+ static float magN = 0.4f;
+ static float magE = 0.0f;
+ static float magD = 0.3f;
+
+ static float R_MAG = 0.0025f;
+
+ float H_MAG[21] = {0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f,0.0f};
+
+ // Sequential fusion of XYZ components to spread processing load across
+ // three prediction time steps.
+
+ // Calculate observation jacobians and Kalman gains
+ if (fuseMagData)
+ {
+ static float magXbias = 0.0f;
+ static float magYbias = 0.0f;
+ static float magZbias = 0.0f;
+
+ // Copy required states to local variable names
+ q0 = statesAtMagMeasTime[0];
+ q1 = statesAtMagMeasTime[1];
+ q2 = statesAtMagMeasTime[2];
+ q3 = statesAtMagMeasTime[3];
+ magN = statesAtMagMeasTime[15];
+ magE = statesAtMagMeasTime[16];
+ magD = statesAtMagMeasTime[17];
+ magXbias = statesAtMagMeasTime[18];
+ magYbias = statesAtMagMeasTime[19];
+ magZbias = statesAtMagMeasTime[20];
+
+ // rotate predicted earth components into body axes and calculate
+ // predicted measurments
+ DCM[0][0] = q0*q0 + q1*q1 - q2*q2 - q3*q3;
+ DCM[0][1] = 2*(q1*q2 + q0*q3);
+ DCM[0][2] = 2*(q1*q3-q0*q2);
+ DCM[1][0] = 2*(q1*q2 - q0*q3);
+ DCM[1][1] = q0*q0 - q1*q1 + q2*q2 - q3*q3;
+ DCM[1][2] = 2*(q2*q3 + q0*q1);
+ DCM[2][0] = 2*(q1*q3 + q0*q2);
+ DCM[2][1] = 2*(q2*q3 - q0*q1);
+ DCM[2][2] = q0*q0 - q1*q1 - q2*q2 + q3*q3;
+ MagPred[0] = DCM[0][0]*magN + DCM[0][1]*magE + DCM[0][2]*magD + magXbias;
+ MagPred[1] = DCM[1][0]*magN + DCM[1][1]*magE + DCM[1][2]*magD + magYbias;
+ MagPred[2] = DCM[2][0]*magN + DCM[2][1]*magE + DCM[2][2]*magD + magZbias;
+
+ // scale magnetometer observation error with total angular rate
+ R_MAG = 0.0025f + sq(0.05f*dAngIMU.length()/dtIMU);
+
+ // Calculate observation jacobians
+ SH_MAG[0] = 2*magD*q3 + 2*magE*q2 + 2*magN*q1;
+ SH_MAG[1] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
+ SH_MAG[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
+ SH_MAG[3] = sq(q3);
+ SH_MAG[4] = sq(q2);
+ SH_MAG[5] = sq(q1);
+ SH_MAG[6] = sq(q0);
+ SH_MAG[7] = 2*magN*q0;
+ SH_MAG[8] = 2*magE*q3;
+
+ for (uint8_t i=0; i<=20; i++) H_MAG[i] = 0;
+ H_MAG[0] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ H_MAG[1] = SH_MAG[0];
+ H_MAG[2] = 2*magE*q1 - 2*magD*q0 - 2*magN*q2;
+ H_MAG[3] = SH_MAG[2];
+ H_MAG[15] = SH_MAG[5] - SH_MAG[4] - SH_MAG[3] + SH_MAG[6];
+ H_MAG[16] = 2*q0*q3 + 2*q1*q2;
+ H_MAG[17] = 2*q1*q3 - 2*q0*q2;
+ H_MAG[18] = 1.0f;
+
+ // Calculate Kalman gain
+ SK_MX[0] = 1/(P[18][18] + R_MAG + P[1][18]*SH_MAG[0] + P[3][18]*SH_MAG[2] - P[15][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) - (2*magD*q0 - 2*magE*q1 + 2*magN*q2)*(P[18][2] + P[1][2]*SH_MAG[0] + P[3][2]*SH_MAG[2] - P[15][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][2]*(2*q0*q3 + 2*q1*q2) - P[17][2]*(2*q0*q2 - 2*q1*q3) - P[2][2]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[18][0] + P[1][0]*SH_MAG[0] + P[3][0]*SH_MAG[2] - P[15][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][0]*(2*q0*q3 + 2*q1*q2) - P[17][0]*(2*q0*q2 - 2*q1*q3) - P[2][0]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[18][1] + P[1][1]*SH_MAG[0] + P[3][1]*SH_MAG[2] - P[15][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][1]*(2*q0*q3 + 2*q1*q2) - P[17][1]*(2*q0*q2 - 2*q1*q3) - P[2][1]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[18][3] + P[1][3]*SH_MAG[0] + P[3][3]*SH_MAG[2] - P[15][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][3]*(2*q0*q3 + 2*q1*q2) - P[17][3]*(2*q0*q2 - 2*q1*q3) - P[2][3]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[18][15] + P[1][15]*SH_MAG[0] + P[3][15]*SH_MAG[2] - P[15][15]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][15]*(2*q0*q3 + 2*q1*q2) - P[17][15]*(2*q0*q2 - 2*q1*q3) - P[2][15]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][18]*(2*q0*q3 + 2*q1*q2) - P[17][18]*(2*q0*q2 - 2*q1*q3) - P[2][18]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + (2*q0*q3 + 2*q1*q2)*(P[18][16] + P[1][16]*SH_MAG[0] + P[3][16]*SH_MAG[2] - P[15][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][16]*(2*q0*q3 + 2*q1*q2) - P[17][16]*(2*q0*q2 - 2*q1*q3) - P[2][16]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[18][17] + P[1][17]*SH_MAG[0] + P[3][17]*SH_MAG[2] - P[15][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[16][17]*(2*q0*q3 + 2*q1*q2) - P[17][17]*(2*q0*q2 - 2*q1*q3) - P[2][17]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6];
+ SK_MX[2] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
+ SK_MX[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ SK_MX[4] = 2*q0*q2 - 2*q1*q3;
+ SK_MX[5] = 2*q0*q3 + 2*q1*q2;
+ Kfusion[0] = SK_MX[0]*(P[0][18] + P[0][1]*SH_MAG[0] + P[0][3]*SH_MAG[2] + P[0][0]*SK_MX[3] - P[0][2]*SK_MX[2] - P[0][15]*SK_MX[1] + P[0][16]*SK_MX[5] - P[0][17]*SK_MX[4]);
+ Kfusion[1] = SK_MX[0]*(P[1][18] + P[1][1]*SH_MAG[0] + P[1][3]*SH_MAG[2] + P[1][0]*SK_MX[3] - P[1][2]*SK_MX[2] - P[1][15]*SK_MX[1] + P[1][16]*SK_MX[5] - P[1][17]*SK_MX[4]);
+ Kfusion[2] = SK_MX[0]*(P[2][18] + P[2][1]*SH_MAG[0] + P[2][3]*SH_MAG[2] + P[2][0]*SK_MX[3] - P[2][2]*SK_MX[2] - P[2][15]*SK_MX[1] + P[2][16]*SK_MX[5] - P[2][17]*SK_MX[4]);
+ Kfusion[3] = SK_MX[0]*(P[3][18] + P[3][1]*SH_MAG[0] + P[3][3]*SH_MAG[2] + P[3][0]*SK_MX[3] - P[3][2]*SK_MX[2] - P[3][15]*SK_MX[1] + P[3][16]*SK_MX[5] - P[3][17]*SK_MX[4]);
+ Kfusion[4] = SK_MX[0]*(P[4][18] + P[4][1]*SH_MAG[0] + P[4][3]*SH_MAG[2] + P[4][0]*SK_MX[3] - P[4][2]*SK_MX[2] - P[4][15]*SK_MX[1] + P[4][16]*SK_MX[5] - P[4][17]*SK_MX[4]);
+ Kfusion[5] = SK_MX[0]*(P[5][18] + P[5][1]*SH_MAG[0] + P[5][3]*SH_MAG[2] + P[5][0]*SK_MX[3] - P[5][2]*SK_MX[2] - P[5][15]*SK_MX[1] + P[5][16]*SK_MX[5] - P[5][17]*SK_MX[4]);
+ Kfusion[6] = SK_MX[0]*(P[6][18] + P[6][1]*SH_MAG[0] + P[6][3]*SH_MAG[2] + P[6][0]*SK_MX[3] - P[6][2]*SK_MX[2] - P[6][15]*SK_MX[1] + P[6][16]*SK_MX[5] - P[6][17]*SK_MX[4]);
+ Kfusion[7] = SK_MX[0]*(P[7][18] + P[7][1]*SH_MAG[0] + P[7][3]*SH_MAG[2] + P[7][0]*SK_MX[3] - P[7][2]*SK_MX[2] - P[7][15]*SK_MX[1] + P[7][16]*SK_MX[5] - P[7][17]*SK_MX[4]);
+ Kfusion[8] = SK_MX[0]*(P[8][18] + P[8][1]*SH_MAG[0] + P[8][3]*SH_MAG[2] + P[8][0]*SK_MX[3] - P[8][2]*SK_MX[2] - P[8][15]*SK_MX[1] + P[8][16]*SK_MX[5] - P[8][17]*SK_MX[4]);
+ Kfusion[9] = SK_MX[0]*(P[9][18] + P[9][1]*SH_MAG[0] + P[9][3]*SH_MAG[2] + P[9][0]*SK_MX[3] - P[9][2]*SK_MX[2] - P[9][15]*SK_MX[1] + P[9][16]*SK_MX[5] - P[9][17]*SK_MX[4]);
+ Kfusion[10] = SK_MX[0]*(P[10][18] + P[10][1]*SH_MAG[0] + P[10][3]*SH_MAG[2] + P[10][0]*SK_MX[3] - P[10][2]*SK_MX[2] - P[10][15]*SK_MX[1] + P[10][16]*SK_MX[5] - P[10][17]*SK_MX[4]);
+ Kfusion[11] = SK_MX[0]*(P[11][18] + P[11][1]*SH_MAG[0] + P[11][3]*SH_MAG[2] + P[11][0]*SK_MX[3] - P[11][2]*SK_MX[2] - P[11][15]*SK_MX[1] + P[11][16]*SK_MX[5] - P[11][17]*SK_MX[4]);
+ Kfusion[12] = SK_MX[0]*(P[12][18] + P[12][1]*SH_MAG[0] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[3] - P[12][2]*SK_MX[2] - P[12][15]*SK_MX[1] + P[12][16]*SK_MX[5] - P[12][17]*SK_MX[4]);
+ Kfusion[13] = SK_MX[0]*(P[13][18] + P[13][1]*SH_MAG[0] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[3] - P[13][2]*SK_MX[2] - P[13][15]*SK_MX[1] + P[13][16]*SK_MX[5] - P[13][17]*SK_MX[4]);
+ Kfusion[14] = SK_MX[0]*(P[14][18] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][15]*SK_MX[1] + P[14][16]*SK_MX[5] - P[14][17]*SK_MX[4]);
+ Kfusion[15] = SK_MX[0]*(P[15][18] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][15]*SK_MX[1] + P[15][16]*SK_MX[5] - P[15][17]*SK_MX[4]);
+ Kfusion[16] = SK_MX[0]*(P[16][18] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][15]*SK_MX[1] + P[16][16]*SK_MX[5] - P[16][17]*SK_MX[4]);
+ Kfusion[17] = SK_MX[0]*(P[17][18] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][15]*SK_MX[1] + P[17][16]*SK_MX[5] - P[17][17]*SK_MX[4]);
+ Kfusion[18] = SK_MX[0]*(P[18][18] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][15]*SK_MX[1] + P[18][16]*SK_MX[5] - P[18][17]*SK_MX[4]);
+ Kfusion[19] = SK_MX[0]*(P[19][18] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][15]*SK_MX[1] + P[19][16]*SK_MX[5] - P[19][17]*SK_MX[4]);
+ Kfusion[20] = SK_MX[0]*(P[20][18] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][15]*SK_MX[1] + P[20][16]*SK_MX[5] - P[20][17]*SK_MX[4]);
+ varInnovMag[0] = 1.0f/SK_MX[0];
+ innovMag[0] = MagPred[0] - magData.x;
+
+ // reset the observation index to 0 (we start by fusing the X
+ // measurement)
+ obsIndex = 0;
+ }
+ else if (obsIndex == 1) // we are now fusing the Y measurement
+ {
+ // Calculate observation jacobians
+ for (unsigned int i=0; i<n_states; i++) H_MAG[i] = 0;
+ H_MAG[0] = SH_MAG[2];
+ H_MAG[1] = SH_MAG[1];
+ H_MAG[2] = SH_MAG[0];
+ H_MAG[3] = 2*magD*q2 - SH_MAG[8] - SH_MAG[7];
+ H_MAG[15] = 2*q1*q2 - 2*q0*q3;
+ H_MAG[16] = SH_MAG[4] - SH_MAG[3] - SH_MAG[5] + SH_MAG[6];
+ H_MAG[17] = 2*q0*q1 + 2*q2*q3;
+ H_MAG[19] = 1;
+
+ // Calculate Kalman gain
+ SK_MY[0] = 1/(P[19][19] + R_MAG + P[0][19]*SH_MAG[2] + P[1][19]*SH_MAG[1] + P[2][19]*SH_MAG[0] - P[16][19]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[19][15] + P[0][15]*SH_MAG[2] + P[1][15]*SH_MAG[1] + P[2][15]*SH_MAG[0] - P[16][15]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][15]*(2*q0*q3 - 2*q1*q2) + P[17][15]*(2*q0*q1 + 2*q2*q3) - P[3][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[19][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[16][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][17]*(2*q0*q3 - 2*q1*q2) + P[17][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[16][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][3]*(2*q0*q3 - 2*q1*q2) + P[17][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[15][19]*(2*q0*q3 - 2*q1*q2) + P[17][19]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[19][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[16][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][0]*(2*q0*q3 - 2*q1*q2) + P[17][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[19][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[16][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][1]*(2*q0*q3 - 2*q1*q2) + P[17][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[19][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[16][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][2]*(2*q0*q3 - 2*q1*q2) + P[17][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[16][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[15][16]*(2*q0*q3 - 2*q1*q2) + P[17][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6];
+ SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ SK_MY[3] = 2*q0*q3 - 2*q1*q2;
+ SK_MY[4] = 2*q0*q1 + 2*q2*q3;
+ Kfusion[0] = SK_MY[0]*(P[0][19] + P[0][0]*SH_MAG[2] + P[0][1]*SH_MAG[1] + P[0][2]*SH_MAG[0] - P[0][3]*SK_MY[2] - P[0][16]*SK_MY[1] - P[0][15]*SK_MY[3] + P[0][17]*SK_MY[4]);
+ Kfusion[1] = SK_MY[0]*(P[1][19] + P[1][0]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[1][2]*SH_MAG[0] - P[1][3]*SK_MY[2] - P[1][16]*SK_MY[1] - P[1][15]*SK_MY[3] + P[1][17]*SK_MY[4]);
+ Kfusion[2] = SK_MY[0]*(P[2][19] + P[2][0]*SH_MAG[2] + P[2][1]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[2][3]*SK_MY[2] - P[2][16]*SK_MY[1] - P[2][15]*SK_MY[3] + P[2][17]*SK_MY[4]);
+ Kfusion[3] = SK_MY[0]*(P[3][19] + P[3][0]*SH_MAG[2] + P[3][1]*SH_MAG[1] + P[3][2]*SH_MAG[0] - P[3][3]*SK_MY[2] - P[3][16]*SK_MY[1] - P[3][15]*SK_MY[3] + P[3][17]*SK_MY[4]);
+ Kfusion[4] = SK_MY[0]*(P[4][19] + P[4][0]*SH_MAG[2] + P[4][1]*SH_MAG[1] + P[4][2]*SH_MAG[0] - P[4][3]*SK_MY[2] - P[4][16]*SK_MY[1] - P[4][15]*SK_MY[3] + P[4][17]*SK_MY[4]);
+ Kfusion[5] = SK_MY[0]*(P[5][19] + P[5][0]*SH_MAG[2] + P[5][1]*SH_MAG[1] + P[5][2]*SH_MAG[0] - P[5][3]*SK_MY[2] - P[5][16]*SK_MY[1] - P[5][15]*SK_MY[3] + P[5][17]*SK_MY[4]);
+ Kfusion[6] = SK_MY[0]*(P[6][19] + P[6][0]*SH_MAG[2] + P[6][1]*SH_MAG[1] + P[6][2]*SH_MAG[0] - P[6][3]*SK_MY[2] - P[6][16]*SK_MY[1] - P[6][15]*SK_MY[3] + P[6][17]*SK_MY[4]);
+ Kfusion[7] = SK_MY[0]*(P[7][19] + P[7][0]*SH_MAG[2] + P[7][1]*SH_MAG[1] + P[7][2]*SH_MAG[0] - P[7][3]*SK_MY[2] - P[7][16]*SK_MY[1] - P[7][15]*SK_MY[3] + P[7][17]*SK_MY[4]);
+ Kfusion[8] = SK_MY[0]*(P[8][19] + P[8][0]*SH_MAG[2] + P[8][1]*SH_MAG[1] + P[8][2]*SH_MAG[0] - P[8][3]*SK_MY[2] - P[8][16]*SK_MY[1] - P[8][15]*SK_MY[3] + P[8][17]*SK_MY[4]);
+ Kfusion[9] = SK_MY[0]*(P[9][19] + P[9][0]*SH_MAG[2] + P[9][1]*SH_MAG[1] + P[9][2]*SH_MAG[0] - P[9][3]*SK_MY[2] - P[9][16]*SK_MY[1] - P[9][15]*SK_MY[3] + P[9][17]*SK_MY[4]);
+ Kfusion[10] = SK_MY[0]*(P[10][19] + P[10][0]*SH_MAG[2] + P[10][1]*SH_MAG[1] + P[10][2]*SH_MAG[0] - P[10][3]*SK_MY[2] - P[10][16]*SK_MY[1] - P[10][15]*SK_MY[3] + P[10][17]*SK_MY[4]);
+ Kfusion[11] = SK_MY[0]*(P[11][19] + P[11][0]*SH_MAG[2] + P[11][1]*SH_MAG[1] + P[11][2]*SH_MAG[0] - P[11][3]*SK_MY[2] - P[11][16]*SK_MY[1] - P[11][15]*SK_MY[3] + P[11][17]*SK_MY[4]);
+ Kfusion[12] = SK_MY[0]*(P[12][19] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][16]*SK_MY[1] - P[12][15]*SK_MY[3] + P[12][17]*SK_MY[4]);
+ Kfusion[13] = SK_MY[0]*(P[13][19] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][16]*SK_MY[1] - P[13][15]*SK_MY[3] + P[13][17]*SK_MY[4]);
+ Kfusion[14] = SK_MY[0]*(P[14][19] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][16]*SK_MY[1] - P[14][15]*SK_MY[3] + P[14][17]*SK_MY[4]);
+ Kfusion[15] = SK_MY[0]*(P[15][19] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][16]*SK_MY[1] - P[15][15]*SK_MY[3] + P[15][17]*SK_MY[4]);
+ Kfusion[16] = SK_MY[0]*(P[16][19] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][16]*SK_MY[1] - P[16][15]*SK_MY[3] + P[16][17]*SK_MY[4]);
+ Kfusion[17] = SK_MY[0]*(P[17][19] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][16]*SK_MY[1] - P[17][15]*SK_MY[3] + P[17][17]*SK_MY[4]);
+ Kfusion[18] = SK_MY[0]*(P[18][19] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][16]*SK_MY[1] - P[18][15]*SK_MY[3] + P[18][17]*SK_MY[4]);
+ Kfusion[19] = SK_MY[0]*(P[19][19] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][16]*SK_MY[1] - P[19][15]*SK_MY[3] + P[19][17]*SK_MY[4]);
+ Kfusion[20] = SK_MY[0]*(P[20][19] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][16]*SK_MY[1] - P[20][15]*SK_MY[3] + P[20][17]*SK_MY[4]);
+ varInnovMag[1] = 1.0f/SK_MY[0];
+ innovMag[1] = MagPred[1] - magData.y;
+ }
+ else if (obsIndex == 2) // we are now fusing the Z measurement
+ {
+ // Calculate observation jacobians
+ for (uint8_t i=0; i<=20; i++) H_MAG[i] = 0;
+ H_MAG[0] = SH_MAG[1];
+ H_MAG[1] = 2*magN*q3 - 2*magE*q0 - 2*magD*q1;
+ H_MAG[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ H_MAG[3] = SH_MAG[0];
+ H_MAG[15] = 2*q0*q2 + 2*q1*q3;
+ H_MAG[16] = 2*q2*q3 - 2*q0*q1;
+ H_MAG[17] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
+ H_MAG[20] = 1;
+
+ // Calculate Kalman gain
+ SK_MZ[0] = 1/(P[20][20] + R_MAG + P[0][20]*SH_MAG[1] + P[3][20]*SH_MAG[0] + P[17][20]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) - (2*magD*q1 + 2*magE*q0 - 2*magN*q3)*(P[20][1] + P[0][1]*SH_MAG[1] + P[3][1]*SH_MAG[0] + P[17][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][1]*(2*q0*q2 + 2*q1*q3) - P[16][1]*(2*q0*q1 - 2*q2*q3) - P[1][1]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][2] + P[0][2]*SH_MAG[1] + P[3][2]*SH_MAG[0] + P[17][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][2]*(2*q0*q2 + 2*q1*q3) - P[16][2]*(2*q0*q1 - 2*q2*q3) - P[1][2]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][0] + P[0][0]*SH_MAG[1] + P[3][0]*SH_MAG[0] + P[17][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][0]*(2*q0*q2 + 2*q1*q3) - P[16][0]*(2*q0*q1 - 2*q2*q3) - P[1][0]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][3] + P[0][3]*SH_MAG[1] + P[3][3]*SH_MAG[0] + P[17][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][3]*(2*q0*q2 + 2*q1*q3) - P[16][3]*(2*q0*q1 - 2*q2*q3) - P[1][3]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[1] + P[3][17]*SH_MAG[0] + P[17][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][17]*(2*q0*q2 + 2*q1*q3) - P[16][17]*(2*q0*q1 - 2*q2*q3) - P[1][17]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[15][20]*(2*q0*q2 + 2*q1*q3) - P[16][20]*(2*q0*q1 - 2*q2*q3) - P[1][20]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + (2*q0*q2 + 2*q1*q3)*(P[20][15] + P[0][15]*SH_MAG[1] + P[3][15]*SH_MAG[0] + P[17][15]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][15]*(2*q0*q2 + 2*q1*q3) - P[16][15]*(2*q0*q1 - 2*q2*q3) - P[1][15]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][15]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[20][16] + P[0][16]*SH_MAG[1] + P[3][16]*SH_MAG[0] + P[17][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[15][16]*(2*q0*q2 + 2*q1*q3) - P[16][16]*(2*q0*q1 - 2*q2*q3) - P[1][16]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
+ SK_MZ[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
+ SK_MZ[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ SK_MZ[4] = 2*q0*q1 - 2*q2*q3;
+ SK_MZ[5] = 2*q0*q2 + 2*q1*q3;
+ Kfusion[0] = SK_MZ[0]*(P[0][20] + P[0][0]*SH_MAG[1] + P[0][3]*SH_MAG[0] - P[0][1]*SK_MZ[2] + P[0][2]*SK_MZ[3] + P[0][17]*SK_MZ[1] + P[0][15]*SK_MZ[5] - P[0][16]*SK_MZ[4]);
+ Kfusion[1] = SK_MZ[0]*(P[1][20] + P[1][0]*SH_MAG[1] + P[1][3]*SH_MAG[0] - P[1][1]*SK_MZ[2] + P[1][2]*SK_MZ[3] + P[1][17]*SK_MZ[1] + P[1][15]*SK_MZ[5] - P[1][16]*SK_MZ[4]);
+ Kfusion[2] = SK_MZ[0]*(P[2][20] + P[2][0]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[2][1]*SK_MZ[2] + P[2][2]*SK_MZ[3] + P[2][17]*SK_MZ[1] + P[2][15]*SK_MZ[5] - P[2][16]*SK_MZ[4]);
+ Kfusion[3] = SK_MZ[0]*(P[3][20] + P[3][0]*SH_MAG[1] + P[3][3]*SH_MAG[0] - P[3][1]*SK_MZ[2] + P[3][2]*SK_MZ[3] + P[3][17]*SK_MZ[1] + P[3][15]*SK_MZ[5] - P[3][16]*SK_MZ[4]);
+ Kfusion[4] = SK_MZ[0]*(P[4][20] + P[4][0]*SH_MAG[1] + P[4][3]*SH_MAG[0] - P[4][1]*SK_MZ[2] + P[4][2]*SK_MZ[3] + P[4][17]*SK_MZ[1] + P[4][15]*SK_MZ[5] - P[4][16]*SK_MZ[4]);
+ Kfusion[5] = SK_MZ[0]*(P[5][20] + P[5][0]*SH_MAG[1] + P[5][3]*SH_MAG[0] - P[5][1]*SK_MZ[2] + P[5][2]*SK_MZ[3] + P[5][17]*SK_MZ[1] + P[5][15]*SK_MZ[5] - P[5][16]*SK_MZ[4]);
+ Kfusion[6] = SK_MZ[0]*(P[6][20] + P[6][0]*SH_MAG[1] + P[6][3]*SH_MAG[0] - P[6][1]*SK_MZ[2] + P[6][2]*SK_MZ[3] + P[6][17]*SK_MZ[1] + P[6][15]*SK_MZ[5] - P[6][16]*SK_MZ[4]);
+ Kfusion[7] = SK_MZ[0]*(P[7][20] + P[7][0]*SH_MAG[1] + P[7][3]*SH_MAG[0] - P[7][1]*SK_MZ[2] + P[7][2]*SK_MZ[3] + P[7][17]*SK_MZ[1] + P[7][15]*SK_MZ[5] - P[7][16]*SK_MZ[4]);
+ Kfusion[8] = SK_MZ[0]*(P[8][20] + P[8][0]*SH_MAG[1] + P[8][3]*SH_MAG[0] - P[8][1]*SK_MZ[2] + P[8][2]*SK_MZ[3] + P[8][17]*SK_MZ[1] + P[8][15]*SK_MZ[5] - P[8][16]*SK_MZ[4]);
+ Kfusion[9] = SK_MZ[0]*(P[9][20] + P[9][0]*SH_MAG[1] + P[9][3]*SH_MAG[0] - P[9][1]*SK_MZ[2] + P[9][2]*SK_MZ[3] + P[9][17]*SK_MZ[1] + P[9][15]*SK_MZ[5] - P[9][16]*SK_MZ[4]);
+ Kfusion[10] = SK_MZ[0]*(P[10][20] + P[10][0]*SH_MAG[1] + P[10][3]*SH_MAG[0] - P[10][1]*SK_MZ[2] + P[10][2]*SK_MZ[3] + P[10][17]*SK_MZ[1] + P[10][15]*SK_MZ[5] - P[10][16]*SK_MZ[4]);
+ Kfusion[11] = SK_MZ[0]*(P[11][20] + P[11][0]*SH_MAG[1] + P[11][3]*SH_MAG[0] - P[11][1]*SK_MZ[2] + P[11][2]*SK_MZ[3] + P[11][17]*SK_MZ[1] + P[11][15]*SK_MZ[5] - P[11][16]*SK_MZ[4]);
+ Kfusion[12] = SK_MZ[0]*(P[12][20] + P[12][0]*SH_MAG[1] + P[12][3]*SH_MAG[0] - P[12][1]*SK_MZ[2] + P[12][2]*SK_MZ[3] + P[12][17]*SK_MZ[1] + P[12][15]*SK_MZ[5] - P[12][16]*SK_MZ[4]);
+ Kfusion[13] = SK_MZ[0]*(P[13][20] + P[13][0]*SH_MAG[1] + P[13][3]*SH_MAG[0] - P[13][1]*SK_MZ[2] + P[13][2]*SK_MZ[3] + P[13][17]*SK_MZ[1] + P[13][15]*SK_MZ[5] - P[13][16]*SK_MZ[4]);
+ Kfusion[14] = SK_MZ[0]*(P[14][20] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][17]*SK_MZ[1] + P[14][15]*SK_MZ[5] - P[14][16]*SK_MZ[4]);
+ Kfusion[15] = SK_MZ[0]*(P[15][20] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][17]*SK_MZ[1] + P[15][15]*SK_MZ[5] - P[15][16]*SK_MZ[4]);
+ Kfusion[16] = SK_MZ[0]*(P[16][20] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][17]*SK_MZ[1] + P[16][15]*SK_MZ[5] - P[16][16]*SK_MZ[4]);
+ Kfusion[17] = SK_MZ[0]*(P[17][20] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][17]*SK_MZ[1] + P[17][15]*SK_MZ[5] - P[17][16]*SK_MZ[4]);
+ Kfusion[18] = SK_MZ[0]*(P[18][20] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][17]*SK_MZ[1] + P[18][15]*SK_MZ[5] - P[18][16]*SK_MZ[4]);
+ Kfusion[19] = SK_MZ[0]*(P[19][20] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][17]*SK_MZ[1] + P[19][15]*SK_MZ[5] - P[19][16]*SK_MZ[4]);
+ Kfusion[20] = SK_MZ[0]*(P[20][20] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][17]*SK_MZ[1] + P[20][15]*SK_MZ[5] - P[20][16]*SK_MZ[4]);
+ varInnovMag[2] = 1.0f/SK_MZ[0];
+ innovMag[2] = MagPred[2] - magData.z;
+
+ }
+
+ // Check the innovation for consistency and don't fuse if > 5Sigma
+ if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0)
+ {
+ // correct the state vector
+ for (uint8_t j= 0; j<=indexLimit; j++)
+ {
+ states[j] = states[j] - Kfusion[j] * innovMag[obsIndex];
+ }
+ // normalise the quaternion states
+ float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12)
+ {
+ for (uint8_t j= 0; j<=3; j++)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[j] = states[j] * quatMagInv;
+ }
+ }
+ // correct the covariance P = (I - K*H)*P
+ // take advantage of the empty columns in KH to reduce the
+ // number of operations
+ for (uint8_t i = 0; i<=indexLimit; i++)
+ {
+ for (uint8_t j = 0; j<=3; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_MAG[j];
+ }
+ for (uint8_t j = 4; j<=17; j++) KH[i][j] = 0.0f;
+ if (!onGround)
+ {
+ for (uint8_t j = 15; j<=20; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_MAG[j];
+ }
+ }
+ else
+ {
+ for (uint8_t j = 15; j<=20; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ }
+ }
+ for (uint8_t i = 0; i<=indexLimit; i++)
+ {
+ for (uint8_t j = 0; j<=indexLimit; j++)
+ {
+ KHP[i][j] = 0.0f;
+ for (uint8_t k = 0; k<=3; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ if (!onGround)
+ {
+ for (uint8_t k = 15; k<=20; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ }
+ }
+ }
+ }
+ for (uint8_t i = 0; i<=indexLimit; i++)
+ {
+ for (uint8_t j = 0; j<=indexLimit; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
+ obsIndex = obsIndex + 1;
+
+ ForceSymmetry();
+ ConstrainVariances();
+}
+
+void AttPosEKF::FuseAirspeed()
+{
+ float vn;
+ float ve;
+ float vd;
+ float vwn;
+ float vwe;
+ const float R_TAS = 2.0f;
+ float SH_TAS[3];
+ float Kfusion[21];
+ float VtasPred;
+
+ // Copy required states to local variable names
+ vn = statesAtVtasMeasTime[4];
+ ve = statesAtVtasMeasTime[5];
+ vd = statesAtVtasMeasTime[6];
+ vwn = statesAtVtasMeasTime[13];
+ vwe = statesAtVtasMeasTime[14];
+
+ // Need to check that it is flying before fusing airspeed data
+ // Calculate the predicted airspeed
+ VtasPred = sqrtf((ve - vwe)*(ve - vwe) + (vn - vwn)*(vn - vwn) + vd*vd);
+ // Perform fusion of True Airspeed measurement
+ if (useAirspeed && fuseVtasData && (VtasPred > 1.0f) && (VtasMeas > 8.0f))
+ {
+ // Calculate observation jacobians
+ SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
+ SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2*vwe))/2.0f;
+ SH_TAS[2] = (SH_TAS[0]*(2.0f*vn - 2*vwn))/2.0f;
+
+ float H_TAS[21];
+ for (uint8_t i=0; i<=20; i++) H_TAS[i] = 0.0f;
+ H_TAS[4] = SH_TAS[2];
+ H_TAS[5] = SH_TAS[1];
+ H_TAS[6] = vd*SH_TAS[0];
+ H_TAS[13] = -SH_TAS[2];
+ H_TAS[14] = -SH_TAS[1];
+
+ // Calculate Kalman gains
+ float SK_TAS = 1.0f/(R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[13][4]*SH_TAS[2] - P[14][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[13][5]*SH_TAS[2] - P[14][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][13]*SH_TAS[2] + P[5][13]*SH_TAS[1] - P[13][13]*SH_TAS[2] - P[14][13]*SH_TAS[1] + P[6][13]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][14]*SH_TAS[2] + P[5][14]*SH_TAS[1] - P[13][14]*SH_TAS[2] - P[14][14]*SH_TAS[1] + P[6][14]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[13][6]*SH_TAS[2] - P[14][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
+ Kfusion[0] = SK_TAS*(P[0][4]*SH_TAS[2] - P[0][13]*SH_TAS[2] + P[0][5]*SH_TAS[1] - P[0][14]*SH_TAS[1] + P[0][6]*vd*SH_TAS[0]);
+ Kfusion[1] = SK_TAS*(P[1][4]*SH_TAS[2] - P[1][13]*SH_TAS[2] + P[1][5]*SH_TAS[1] - P[1][14]*SH_TAS[1] + P[1][6]*vd*SH_TAS[0]);
+ Kfusion[2] = SK_TAS*(P[2][4]*SH_TAS[2] - P[2][13]*SH_TAS[2] + P[2][5]*SH_TAS[1] - P[2][14]*SH_TAS[1] + P[2][6]*vd*SH_TAS[0]);
+ Kfusion[3] = SK_TAS*(P[3][4]*SH_TAS[2] - P[3][13]*SH_TAS[2] + P[3][5]*SH_TAS[1] - P[3][14]*SH_TAS[1] + P[3][6]*vd*SH_TAS[0]);
+ Kfusion[4] = SK_TAS*(P[4][4]*SH_TAS[2] - P[4][13]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[4][14]*SH_TAS[1] + P[4][6]*vd*SH_TAS[0]);
+ Kfusion[5] = SK_TAS*(P[5][4]*SH_TAS[2] - P[5][13]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[5][14]*SH_TAS[1] + P[5][6]*vd*SH_TAS[0]);
+ Kfusion[6] = SK_TAS*(P[6][4]*SH_TAS[2] - P[6][13]*SH_TAS[2] + P[6][5]*SH_TAS[1] - P[6][14]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]);
+ Kfusion[7] = SK_TAS*(P[7][4]*SH_TAS[2] - P[7][13]*SH_TAS[2] + P[7][5]*SH_TAS[1] - P[7][14]*SH_TAS[1] + P[7][6]*vd*SH_TAS[0]);
+ Kfusion[8] = SK_TAS*(P[8][4]*SH_TAS[2] - P[8][13]*SH_TAS[2] + P[8][5]*SH_TAS[1] - P[8][14]*SH_TAS[1] + P[8][6]*vd*SH_TAS[0]);
+ Kfusion[9] = SK_TAS*(P[9][4]*SH_TAS[2] - P[9][13]*SH_TAS[2] + P[9][5]*SH_TAS[1] - P[9][14]*SH_TAS[1] + P[9][6]*vd*SH_TAS[0]);
+ Kfusion[10] = SK_TAS*(P[10][4]*SH_TAS[2] - P[10][13]*SH_TAS[2] + P[10][5]*SH_TAS[1] - P[10][14]*SH_TAS[1] + P[10][6]*vd*SH_TAS[0]);
+ Kfusion[11] = SK_TAS*(P[11][4]*SH_TAS[2] - P[11][13]*SH_TAS[2] + P[11][5]*SH_TAS[1] - P[11][14]*SH_TAS[1] + P[11][6]*vd*SH_TAS[0]);
+ Kfusion[12] = SK_TAS*(P[12][4]*SH_TAS[2] - P[12][13]*SH_TAS[2] + P[12][5]*SH_TAS[1] - P[12][14]*SH_TAS[1] + P[12][6]*vd*SH_TAS[0]);
+ Kfusion[13] = SK_TAS*(P[13][4]*SH_TAS[2] - P[13][13]*SH_TAS[2] + P[13][5]*SH_TAS[1] - P[13][14]*SH_TAS[1] + P[13][6]*vd*SH_TAS[0]);
+ Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][13]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][14]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
+ Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][13]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][14]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
+ Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][13]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][14]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
+ Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][13]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][14]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
+ Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][13]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][14]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
+ Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][13]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][14]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
+ Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][13]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][14]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
+ varInnovVtas = 1.0f/SK_TAS;
+
+ // Calculate the measurement innovation
+ innovVtas = VtasPred - VtasMeas;
+ // Check the innovation for consistency and don't fuse if > 5Sigma
+ if ((innovVtas*innovVtas*SK_TAS) < 25.0)
+ {
+ // correct the state vector
+ for (uint8_t j=0; j<=20; j++)
+ {
+ states[j] = states[j] - Kfusion[j] * innovVtas;
+ }
+ // normalise the quaternion states
+ float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12f)
+ {
+ for (uint8_t j= 0; j<=3; j++)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[j] = states[j] * quatMagInv;
+ }
+ }
+ // correct the covariance P = (I - K*H)*P
+ // take advantage of the empty columns in H to reduce the
+ // number of operations
+ for (uint8_t i = 0; i<=20; i++)
+ {
+ for (uint8_t j = 0; j<=3; j++) KH[i][j] = 0.0;
+ for (uint8_t j = 4; j<=6; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_TAS[j];
+ }
+ for (uint8_t j = 7; j<=12; j++) KH[i][j] = 0.0;
+ for (uint8_t j = 13; j<=14; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_TAS[j];
+ }
+ for (uint8_t j = 15; j<=20; j++) KH[i][j] = 0.0;
+ }
+ for (uint8_t i = 0; i<=20; i++)
+ {
+ for (uint8_t j = 0; j<=20; j++)
+ {
+ KHP[i][j] = 0.0;
+ for (uint8_t k = 4; k<=6; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ for (uint8_t k = 13; k<=14; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ }
+ }
+ for (uint8_t i = 0; i<=20; i++)
+ {
+ for (uint8_t j = 0; j<=20; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
+ }
+
+ ForceSymmetry();
+ ConstrainVariances();
+}
+
+void AttPosEKF::zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
+{
+ uint8_t row;
+ uint8_t col;
+ for (row=first; row<=last; row++)
+ {
+ for (col=0; col<n_states; col++)
+ {
+ covMat[row][col] = 0.0;
+ }
+ }
+}
+
+void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
+{
+ uint8_t row;
+ uint8_t col;
+ for (col=first; col<=last; col++)
+ {
+ for (row=0; row < n_states; row++)
+ {
+ covMat[row][col] = 0.0;
+ }
+ }
+}
+
+float AttPosEKF::sq(float valIn)
+{
+ return valIn*valIn;
+}
+
+// Store states in a history array along with time stamp
+void AttPosEKF::StoreStates(uint64_t timestamp_ms)
+{
+ for (unsigned i=0; i<n_states; i++)
+ storedStates[i][storeIndex] = states[i];
+ statetimeStamp[storeIndex] = timestamp_ms;
+ storeIndex++;
+ if (storeIndex == data_buffer_size)
+ storeIndex = 0;
+}
+
+void AttPosEKF::ResetStoredStates()
+{
+ // reset all stored states
+ memset(&storedStates[0][0], 0, sizeof(storedStates));
+ memset(&statetimeStamp[0], 0, sizeof(statetimeStamp));
+
+ // reset store index to first
+ storeIndex = 0;
+
+ // overwrite all existing states
+ for (unsigned i = 0; i < n_states; i++) {
+ storedStates[i][storeIndex] = states[i];
+ }
+
+ statetimeStamp[storeIndex] = millis();
+
+ // increment to next storage index
+ storeIndex++;
+}
+
+// Output the state vector stored at the time that best matches that specified by msec
+int AttPosEKF::RecallStates(float statesForFusion[n_states], uint64_t msec)
+{
+ int ret = 0;
+
+ // int64_t bestTimeDelta = 200;
+ // unsigned bestStoreIndex = 0;
+ // for (unsigned storeIndex = 0; storeIndex < data_buffer_size; storeIndex++)
+ // {
+ // // The time delta can also end up as negative number,
+ // // since we might compare future to past or past to future
+ // // therefore cast to int64.
+ // int64_t timeDelta = (int64_t)msec - (int64_t)statetimeStamp[storeIndex];
+ // if (timeDelta < 0) {
+ // timeDelta = -timeDelta;
+ // }
+
+ // if (timeDelta < bestTimeDelta)
+ // {
+ // bestStoreIndex = storeIndex;
+ // bestTimeDelta = timeDelta;
+ // }
+ // }
+ // if (bestTimeDelta < 200) // only output stored state if < 200 msec retrieval error
+ // {
+ // for (uint8_t i=0; i < n_states; i++) {
+ // if (isfinite(storedStates[i][bestStoreIndex])) {
+ // statesForFusion[i] = storedStates[i][bestStoreIndex];
+ // } else if (isfinite(states[i])) {
+ // statesForFusion[i] = states[i];
+ // } else {
+ // // There is not much we can do here, except reporting the error we just
+ // // found.
+ // ret++;
+ // }
+ // }
+ // else // otherwise output current state
+ // {
+ for (uint8_t i=0; i < n_states; i++) {
+ if (isfinite(states[i])) {
+ statesForFusion[i] = states[i];
+ } else {
+ ret++;
+ }
+ }
+ // }
+
+ return ret;
+}
+
+void AttPosEKF::quat2Tnb(Mat3f &Tnb, const float (&quat)[4])
+{
+ // Calculate the nav to body cosine matrix
+ float q00 = sq(quat[0]);
+ float q11 = sq(quat[1]);
+ float q22 = sq(quat[2]);
+ float q33 = sq(quat[3]);
+ float q01 = quat[0]*quat[1];
+ float q02 = quat[0]*quat[2];
+ float q03 = quat[0]*quat[3];
+ float q12 = quat[1]*quat[2];
+ float q13 = quat[1]*quat[3];
+ float q23 = quat[2]*quat[3];
+
+ Tnb.x.x = q00 + q11 - q22 - q33;
+ Tnb.y.y = q00 - q11 + q22 - q33;
+ Tnb.z.z = q00 - q11 - q22 + q33;
+ Tnb.y.x = 2*(q12 - q03);
+ Tnb.z.x = 2*(q13 + q02);
+ Tnb.x.y = 2*(q12 + q03);
+ Tnb.z.y = 2*(q23 - q01);
+ Tnb.x.z = 2*(q13 - q02);
+ Tnb.y.z = 2*(q23 + q01);
+}
+
+void AttPosEKF::quat2Tbn(Mat3f &Tbn, const float (&quat)[4])
+{
+ // Calculate the body to nav cosine matrix
+ float q00 = sq(quat[0]);
+ float q11 = sq(quat[1]);
+ float q22 = sq(quat[2]);
+ float q33 = sq(quat[3]);
+ float q01 = quat[0]*quat[1];
+ float q02 = quat[0]*quat[2];
+ float q03 = quat[0]*quat[3];
+ float q12 = quat[1]*quat[2];
+ float q13 = quat[1]*quat[3];
+ float q23 = quat[2]*quat[3];
+
+ Tbn.x.x = q00 + q11 - q22 - q33;
+ Tbn.y.y = q00 - q11 + q22 - q33;
+ Tbn.z.z = q00 - q11 - q22 + q33;
+ Tbn.x.y = 2*(q12 - q03);
+ Tbn.x.z = 2*(q13 + q02);
+ Tbn.y.x = 2*(q12 + q03);
+ Tbn.y.z = 2*(q23 - q01);
+ Tbn.z.x = 2*(q13 - q02);
+ Tbn.z.y = 2*(q23 + q01);
+}
+
+void AttPosEKF::eul2quat(float (&quat)[4], const float (&eul)[3])
+{
+ float u1 = cos(0.5f*eul[0]);
+ float u2 = cos(0.5f*eul[1]);
+ float u3 = cos(0.5f*eul[2]);
+ float u4 = sin(0.5f*eul[0]);
+ float u5 = sin(0.5f*eul[1]);
+ float u6 = sin(0.5f*eul[2]);
+ quat[0] = u1*u2*u3+u4*u5*u6;
+ quat[1] = u4*u2*u3-u1*u5*u6;
+ quat[2] = u1*u5*u3+u4*u2*u6;
+ quat[3] = u1*u2*u6-u4*u5*u3;
+}
+
+void AttPosEKF::quat2eul(float (&y)[3], const float (&u)[4])
+{
+ y[0] = atan2f((2.0f*(u[2]*u[3]+u[0]*u[1])) , (u[0]*u[0]-u[1]*u[1]-u[2]*u[2]+u[3]*u[3]));
+ y[1] = -asinf(2.0f*(u[1]*u[3]-u[0]*u[2]));
+ y[2] = atan2f((2.0f*(u[1]*u[2]+u[0]*u[3])) , (u[0]*u[0]+u[1]*u[1]-u[2]*u[2]-u[3]*u[3]));
+}
+
+void AttPosEKF::calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD)
+{
+ velNED[0] = gpsGndSpd*cosf(gpsCourse);
+ velNED[1] = gpsGndSpd*sinf(gpsCourse);
+ velNED[2] = gpsVelD;
+}
+
+void AttPosEKF::calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
+{
+ posNED[0] = earthRadius * (lat - latRef);
+ posNED[1] = earthRadius * cos(latRef) * (lon - lonRef);
+ posNED[2] = -(hgt - hgtRef);
+}
+
+void AttPosEKF::calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
+{
+ lat = latRef + posNED[0] * earthRadiusInv;
+ lon = lonRef + posNED[1] * earthRadiusInv / cos(latRef);
+ hgt = hgtRef - posNED[2];
+}
+
+void AttPosEKF::OnGroundCheck()
+{
+ onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
+ if (staticMode) {
+ staticMode = !(GPSstatus > GPS_FIX_2D);
+ }
+}
+
+void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude)
+{
+ //Define Earth rotation vector in the NED navigation frame
+ omega.x = earthRate*cosf(latitude);
+ omega.y = 0.0f;
+ omega.z = -earthRate*sinf(latitude);
+}
+
+void AttPosEKF::CovarianceInit()
+{
+ // Calculate the initial covariance matrix P
+ P[0][0] = 0.25f * sq(1.0f*deg2rad);
+ P[1][1] = 0.25f * sq(1.0f*deg2rad);
+ P[2][2] = 0.25f * sq(1.0f*deg2rad);
+ P[3][3] = 0.25f * sq(10.0f*deg2rad);
+ P[4][4] = sq(0.7);
+ P[5][5] = P[4][4];
+ P[6][6] = sq(0.7);
+ P[7][7] = sq(15.0);
+ P[8][8] = P[7][7];
+ P[9][9] = sq(5.0);
+ P[10][10] = sq(0.1*deg2rad*dtIMU);
+ P[11][11] = P[10][10];
+ P[12][12] = P[10][10];
+ P[13][13] = sq(8.0f);
+ P[14][4] = P[13][13];
+ P[15][15] = sq(0.02f);
+ P[16][16] = P[15][15];
+ P[17][17] = P[15][15];
+ P[18][18] = sq(0.02f);
+ P[19][19] = P[18][18];
+ P[20][20] = P[18][18];
+}
+
+float AttPosEKF::ConstrainFloat(float val, float min, float max)
+{
+ return (val > max) ? max : ((val < min) ? min : val);
+}
+
+void AttPosEKF::ConstrainVariances()
+{
+ if (!numericalProtection) {
+ return;
+ }
+
+ // State vector:
+ // 0-3: quaternions (q0, q1, q2, q3)
+ // 4-6: Velocity - m/sec (North, East, Down)
+ // 7-9: Position - m (North, East, Down)
+ // 10-12: Delta Angle bias - rad (X,Y,Z)
+ // 13-14: Wind Vector - m/sec (North,East)
+ // 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
+ // 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
+
+ // Constrain quaternion variances
+ for (unsigned i = 0; i < 4; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+ // Constrain velocitie variances
+ for (unsigned i = 4; i < 7; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
+ }
+
+ // Constrain position variances
+ for (unsigned i = 7; i < 10; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e6f);
+ }
+
+ // Angle bias variances
+ for (unsigned i = 10; i < 13; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, sq(0.175f * dtIMU));
+ }
+
+ // Wind velocity variances
+ for (unsigned i = 13; i < 15; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
+ }
+
+ // Earth magnetic field variances
+ for (unsigned i = 15; i < 18; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+ // Body magnetic field variances
+ for (unsigned i = 18; i < 21; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+}
+
+void AttPosEKF::ConstrainStates()
+{
+ if (!numericalProtection) {
+ return;
+ }
+
+ // State vector:
+ // 0-3: quaternions (q0, q1, q2, q3)
+ // 4-6: Velocity - m/sec (North, East, Down)
+ // 7-9: Position - m (North, East, Down)
+ // 10-12: Delta Angle bias - rad (X,Y,Z)
+ // 13-14: Wind Vector - m/sec (North,East)
+ // 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
+ // 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
+
+
+ // Constrain quaternion
+ for (unsigned i = 0; i < 4; i++) {
+ states[i] = ConstrainFloat(states[i], -1.0f, 1.0f);
+ }
+
+ // Constrain velocities to what GPS can do for us
+ for (unsigned i = 4; i < 7; i++) {
+ states[i] = ConstrainFloat(states[i], -5.0e2f, 5.0e2f);
+ }
+
+ // Constrain position to a reasonable vehicle range (in meters)
+ for (unsigned i = 7; i < 9; i++) {
+ states[i] = ConstrainFloat(states[i], -1.0e6f, 1.0e6f);
+ }
+
+ // Constrain altitude
+ states[9] = ConstrainFloat(states[9], -4.0e4f, 1.0e4f);
+
+ // Angle bias limit - set to 8 degrees / sec
+ for (unsigned i = 10; i < 13; i++) {
+ states[i] = ConstrainFloat(states[i], -0.12f * dtIMU, 0.12f * dtIMU);
+ }
+
+ // Wind velocity limits - assume 120 m/s max velocity
+ for (unsigned i = 13; i < 15; i++) {
+ states[i] = ConstrainFloat(states[i], -120.0f, 120.0f);
+ }
+
+ // Earth magnetic field limits (in Gauss)
+ for (unsigned i = 15; i < 18; i++) {
+ states[i] = ConstrainFloat(states[i], -1.0f, 1.0f);
+ }
+
+ // Body magnetic field variances (in Gauss).
+ // the max offset should be in this range.
+ for (unsigned i = 18; i < 21; i++) {
+ states[i] = ConstrainFloat(states[i], -0.5f, 0.5f);
+ }
+
+}
+
+void AttPosEKF::ForceSymmetry()
+{
+ if (!numericalProtection) {
+ return;
+ }
+
+ // Force symmetry on the covariance matrix to prevent ill-conditioning
+ // of the matrix which would cause the filter to blow-up
+ for (unsigned i = 1; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < i; j++)
+ {
+ P[i][j] = 0.5f * (P[i][j] + P[j][i]);
+ P[j][i] = P[i][j];
+ }
+ }
+}
+
+bool AttPosEKF::FilterHealthy()
+{
+ if (!statesInitialised) {
+ return false;
+ }
+
+ // XXX Check state vector for NaNs and ill-conditioning
+
+ // Check if any of the major inputs timed out
+ if (current_ekf_state.posTimeout || current_ekf_state.velTimeout || current_ekf_state.hgtTimeout) {
+ return false;
+ }
+
+ // Nothing fired, return ok.
+ return true;
+}
+
+/**
+ * Reset the filter position states
+ *
+ * This resets the position to the last GPS measurement
+ * or to zero in case of static position.
+ */
+void AttPosEKF::ResetPosition(void)
+{
+ if (staticMode) {
+ states[7] = 0;
+ states[8] = 0;
+ } else if (GPSstatus >= GPS_FIX_3D) {
+
+ // reset the states from the GPS measurements
+ states[7] = posNE[0];
+ states[8] = posNE[1];
+ }
+}
+
+/**
+ * Reset the height state.
+ *
+ * This resets the height state with the last altitude measurements
+ */
+void AttPosEKF::ResetHeight(void)
+{
+ // write to the state vector
+ states[9] = -hgtMea;
+}
+
+/**
+ * Reset the velocity state.
+ */
+void AttPosEKF::ResetVelocity(void)
+{
+ if (staticMode) {
+ states[4] = 0.0f;
+ states[5] = 0.0f;
+ states[6] = 0.0f;
+ } else if (GPSstatus >= GPS_FIX_3D) {
+
+ states[4] = velNED[0]; // north velocity from last reading
+ states[5] = velNED[1]; // east velocity from last reading
+ states[6] = velNED[2]; // down velocity from last reading
+ }
+}
+
+
+void AttPosEKF::FillErrorReport(struct ekf_status_report *err)
+{
+ for (int i = 0; i < n_states; i++)
+ {
+ err->states[i] = states[i];
+ }
+
+ err->velHealth = current_ekf_state.velHealth;
+ err->posHealth = current_ekf_state.posHealth;
+ err->hgtHealth = current_ekf_state.hgtHealth;
+ err->velTimeout = current_ekf_state.velTimeout;
+ err->posTimeout = current_ekf_state.posTimeout;
+ err->hgtTimeout = current_ekf_state.hgtTimeout;
+}
+
+bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
+ bool err = false;
+
+ // check all states and covariance matrices
+ for (unsigned i = 0; i < n_states; i++) {
+ for (unsigned j = 0; j < n_states; j++) {
+ if (!isfinite(KH[i][j])) {
+
+ err_report->covarianceNaN = true;
+ err = true;
+ } // intermediate result used for covariance updates
+ if (!isfinite(KHP[i][j])) {
+
+ err_report->covarianceNaN = true;
+ err = true;
+ } // intermediate result used for covariance updates
+ if (!isfinite(P[i][j])) {
+
+ err_report->covarianceNaN = true;
+ err = true;
+ } // covariance matrix
+ }
+
+ if (!isfinite(Kfusion[i])) {
+
+ err_report->kalmanGainsNaN = true;
+ err = true;
+ } // Kalman gains
+
+ if (!isfinite(states[i])) {
+
+ err_report->statesNaN = true;
+ err = true;
+ } // state matrix
+ }
+
+ if (err) {
+ FillErrorReport(err_report);
+ }
+
+ return err;
+
+}
+
+/**
+ * Check the filter inputs and bound its operational state
+ *
+ * This check will reset the filter states if required
+ * due to a failure of consistency or timeout checks.
+ * it should be run after the measurement data has been
+ * updated, but before any of the fusion steps are
+ * executed.
+ */
+int AttPosEKF::CheckAndBound()
+{
+
+ // Store the old filter state
+ bool currStaticMode = staticMode;
+
+ // Reset the filter if the states went NaN
+ if (StatesNaN(&last_ekf_error)) {
+
+ InitializeDynamic(velNED, magDeclination);
+
+ return 1;
+ }
+
+ // Reset the filter if the IMU data is too old
+ if (dtIMU > 0.2f) {
+
+ ResetVelocity();
+ ResetPosition();
+ ResetHeight();
+ ResetStoredStates();
+
+ // that's all we can do here, return
+ return 2;
+ }
+
+ // Check if we're on ground - this also sets static mode.
+ OnGroundCheck();
+
+ // Check if we switched between states
+ if (currStaticMode != staticMode) {
+ ResetVelocity();
+ ResetPosition();
+ ResetHeight();
+ ResetStoredStates();
+
+ return 3;
+ }
+
+ return 0;
+}
+
+void AttPosEKF::AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat)
+{
+ float initialRoll, initialPitch;
+ float cosRoll, sinRoll, cosPitch, sinPitch;
+ float magX, magY;
+ float initialHdg, cosHeading, sinHeading;
+
+ initialRoll = atan2(-ay, -az);
+ initialPitch = atan2(ax, -az);
+
+ cosRoll = cosf(initialRoll);
+ sinRoll = sinf(initialRoll);
+ cosPitch = cosf(initialPitch);
+ sinPitch = sinf(initialPitch);
+
+ magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
+
+ magY = my * cosRoll - mz * sinRoll;
+
+ initialHdg = atan2f(-magY, magX);
+ /* true heading is the mag heading minus declination */
+ initialHdg += declination;
+
+ cosRoll = cosf(initialRoll * 0.5f);
+ sinRoll = sinf(initialRoll * 0.5f);
+
+ cosPitch = cosf(initialPitch * 0.5f);
+ sinPitch = sinf(initialPitch * 0.5f);
+
+ cosHeading = cosf(initialHdg * 0.5f);
+ sinHeading = sinf(initialHdg * 0.5f);
+
+ initQuat[0] = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
+ initQuat[1] = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
+ initQuat[2] = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
+ initQuat[3] = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
+}
+
+void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
+{
+
+ // Clear the init flag
+ statesInitialised = false;
+
+ magDeclination = declination;
+
+ ZeroVariables();
+
+ // Calculate initial filter quaternion states from raw measurements
+ float initQuat[4];
+ Vector3f initMagXYZ;
+ initMagXYZ = magData - magBias;
+ AttitudeInit(accel.x, accel.y, accel.z, initMagXYZ.x, initMagXYZ.y, initMagXYZ.z, magDeclination, initQuat);
+
+ // Calculate initial Tbn matrix and rotate Mag measurements into NED
+ // to set initial NED magnetic field states
+ Mat3f DCM;
+ quat2Tbn(DCM, initQuat);
+ Vector3f initMagNED;
+ initMagXYZ = magData - magBias;
+ initMagNED.x = DCM.x.x*initMagXYZ.x + DCM.x.y*initMagXYZ.y + DCM.x.z*initMagXYZ.z;
+ initMagNED.y = DCM.y.x*initMagXYZ.x + DCM.y.y*initMagXYZ.y + DCM.y.z*initMagXYZ.z;
+ initMagNED.z = DCM.z.x*initMagXYZ.x + DCM.z.y*initMagXYZ.y + DCM.z.z*initMagXYZ.z;
+
+
+
+ // write to state vector
+ for (uint8_t j=0; j<=3; j++) states[j] = initQuat[j]; // quaternions
+ for (uint8_t j=0; j<=2; j++) states[j+4] = initvelNED[j]; // velocities
+ for (uint8_t j=0; j<=7; j++) states[j+7] = 0.0f; // positiions, dAngBias, windVel
+ states[15] = initMagNED.x; // Magnetic Field North
+ states[16] = initMagNED.y; // Magnetic Field East
+ states[17] = initMagNED.z; // Magnetic Field Down
+ states[18] = magBias.x; // Magnetic Field Bias X
+ states[19] = magBias.y; // Magnetic Field Bias Y
+ states[20] = magBias.z; // Magnetic Field Bias Z
+
+ statesInitialised = true;
+
+ // initialise the covariance matrix
+ CovarianceInit();
+
+ //Define Earth rotation vector in the NED navigation frame
+ calcEarthRateNED(earthRateNED, latRef);
+
+ //Initialise summed variables used by covariance prediction
+ summedDelAng.x = 0.0f;
+ summedDelAng.y = 0.0f;
+ summedDelAng.z = 0.0f;
+ summedDelVel.x = 0.0f;
+ summedDelVel.y = 0.0f;
+ summedDelVel.z = 0.0f;
+}
+
+void AttPosEKF::InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination)
+{
+ //store initial lat,long and height
+ latRef = referenceLat;
+ lonRef = referenceLon;
+ hgtRef = referenceHgt;
+
+ memset(&last_ekf_error, 0, sizeof(last_ekf_error));
+
+ InitializeDynamic(initvelNED, declination);
+}
+
+void AttPosEKF::ZeroVariables()
+{
+ // Do the data structure init
+ for (unsigned i = 0; i < n_states; i++) {
+ for (unsigned j = 0; j < n_states; j++) {
+ KH[i][j] = 0.0f; // intermediate result used for covariance updates
+ KHP[i][j] = 0.0f; // intermediate result used for covariance updates
+ P[i][j] = 0.0f; // covariance matrix
+ }
+
+ Kfusion[i] = 0.0f; // Kalman gains
+ states[i] = 0.0f; // state matrix
+ }
+
+ for (unsigned i = 0; i < data_buffer_size; i++) {
+
+ for (unsigned j = 0; j < n_states; j++) {
+ storedStates[j][i] = 0.0f;
+ }
+
+ statetimeStamp[i] = 0;
+ }
+
+ memset(&current_ekf_state, 0, sizeof(current_ekf_state));
+}
+
+void AttPosEKF::GetFilterState(struct ekf_status_report *state)
+{
+ memcpy(state, &current_ekf_state, sizeof(state));
+}
+
+void AttPosEKF::GetLastErrorState(struct ekf_status_report *last_error)
+{
+ memcpy(last_error, &last_ekf_error, sizeof(last_error));
+}
diff --git a/src/modules/ekf_att_pos_estimator/estimator_21states.h b/src/modules/ekf_att_pos_estimator/estimator_21states.h
new file mode 100644
index 000000000..a19ff1995
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/estimator_21states.h
@@ -0,0 +1,247 @@
+#pragma once
+
+#include "estimator_utilities.h"
+
+class AttPosEKF {
+
+public:
+
+ AttPosEKF();
+ ~AttPosEKF();
+
+ /* ##############################################
+ *
+ * M A I N F I L T E R P A R A M E T E R S
+ *
+ * ########################################### */
+
+ /*
+ * parameters are defined here and initialised in
+ * the InitialiseParameters() (which is just 20 lines down)
+ */
+
+ float covTimeStepMax; // maximum time allowed between covariance predictions
+ float covDelAngMax; // maximum delta angle between covariance predictions
+ float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
+
+ float yawVarScale;
+ float windVelSigma;
+ float dAngBiasSigma;
+ float dVelBiasSigma;
+ float magEarthSigma;
+ float magBodySigma;
+ float gndHgtSigma;
+
+ float vneSigma;
+ float vdSigma;
+ float posNeSigma;
+ float posDSigma;
+ float magMeasurementSigma;
+ float airspeedMeasurementSigma;
+
+ float gyroProcessNoise;
+ float accelProcessNoise;
+
+ float EAS2TAS; // ratio f true to equivalent airspeed
+
+ void InitialiseParameters()
+ {
+ covTimeStepMax = 0.07f; // maximum time allowed between covariance predictions
+ covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
+ rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
+ EAS2TAS = 1.0f;
+
+ yawVarScale = 1.0f;
+ windVelSigma = 0.1f;
+ dAngBiasSigma = 5.0e-7f;
+ dVelBiasSigma = 1e-4f;
+ magEarthSigma = 3.0e-4f;
+ magBodySigma = 3.0e-4f;
+ gndHgtSigma = 0.02f; // assume 2% terrain gradient 1-sigma
+
+ vneSigma = 0.2f;
+ vdSigma = 0.3f;
+ posNeSigma = 2.0f;
+ posDSigma = 2.0f;
+
+ magMeasurementSigma = 0.05;
+ airspeedMeasurementSigma = 1.4f;
+ gyroProcessNoise = 1.4544411e-2f;
+ accelProcessNoise = 0.5f;
+ }
+
+ // Global variables
+ float KH[n_states][n_states]; // intermediate result used for covariance updates
+ float KHP[n_states][n_states]; // intermediate result used for covariance updates
+ float P[n_states][n_states]; // covariance matrix
+ float Kfusion[n_states]; // Kalman gains
+ float states[n_states]; // state matrix
+ float storedStates[n_states][data_buffer_size]; // state vectors stored for the last 50 time steps
+ uint32_t statetimeStamp[data_buffer_size]; // time stamp for each state vector stored
+
+ float statesAtVelTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
+ float statesAtPosTime[n_states]; // States at the effective measurement time for posNE and velNED measurements
+ float statesAtHgtTime[n_states]; // States at the effective measurement time for the hgtMea measurement
+ float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
+ float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
+
+ Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
+ Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
+ Vector3f summedDelAng; // summed delta angles about the xyz body axes corrected for errors (rad)
+ Vector3f summedDelVel; // summed delta velocities along the XYZ body axes corrected for errors (m/s)
+ float accNavMag; // magnitude of navigation accel (- used to adjust GPS obs variance (m/s^2)
+ Vector3f earthRateNED; // earths angular rate vector in NED (rad/s)
+ Vector3f angRate; // angular rate vector in XYZ body axes measured by the IMU (rad/s)
+ Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
+ Vector3f dVelIMU;
+ Vector3f dAngIMU;
+ float dtIMU; // time lapsed since the last IMU measurement or covariance update (sec)
+ uint8_t fusionModeGPS; // 0 = GPS outputs 3D velocity, 1 = GPS outputs 2D velocity, 2 = GPS outputs no velocity
+ float innovVelPos[6]; // innovation output
+ float varInnovVelPos[6]; // innovation variance output
+
+ float velNED[3]; // North, East, Down velocity obs (m/s)
+ float posNE[2]; // North, East position obs (m)
+ float hgtMea; // measured height (m)
+ float posNED[3]; // North, East Down position (m)
+
+ float innovMag[3]; // innovation output
+ float varInnovMag[3]; // innovation variance output
+ Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
+ float innovVtas; // innovation output
+ float varInnovVtas; // innovation variance output
+ float VtasMeas; // true airspeed measurement (m/s)
+ float magDeclination;
+ float latRef; // WGS-84 latitude of reference point (rad)
+ float lonRef; // WGS-84 longitude of reference point (rad)
+ float hgtRef; // WGS-84 height of reference point (m)
+ Vector3f magBias; // states representing magnetometer bias vector in XYZ body axes
+ uint8_t covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
+
+ // GPS input data variables
+ float gpsCourse;
+ float gpsVelD;
+ float gpsLat;
+ float gpsLon;
+ float gpsHgt;
+ uint8_t GPSstatus;
+
+ // Baro input
+ float baroHgt;
+
+ bool statesInitialised;
+
+ bool fuseVelData; // this boolean causes the posNE and velNED obs to be fused
+ bool fusePosData; // this boolean causes the posNE and velNED obs to be fused
+ bool fuseHgtData; // this boolean causes the hgtMea obs to be fused
+ bool fuseMagData; // boolean true when magnetometer data is to be fused
+ bool fuseVtasData; // boolean true when airspeed data is to be fused
+
+ bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
+ bool staticMode; ///< boolean true if no position feedback is fused
+ bool useAirspeed; ///< boolean true if airspeed data is being used
+ bool useCompass; ///< boolean true if magnetometer data is being used
+
+ struct ekf_status_report current_ekf_state;
+ struct ekf_status_report last_ekf_error;
+
+ bool numericalProtection;
+
+ unsigned storeIndex;
+
+
+void UpdateStrapdownEquationsNED();
+
+void CovariancePrediction(float dt);
+
+void FuseVelposNED();
+
+void FuseMagnetometer();
+
+void FuseAirspeed();
+
+void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
+
+void zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
+
+void quatNorm(float (&quatOut)[4], const float quatIn[4]);
+
+// store staes along with system time stamp in msces
+void StoreStates(uint64_t timestamp_ms);
+
+/**
+ * Recall the state vector.
+ *
+ * Recalls the vector stored at closest time to the one specified by msec
+ *
+ * @return zero on success, integer indicating the number of invalid states on failure.
+ * Does only copy valid states, if the statesForFusion vector was initialized
+ * correctly by the caller, the result can be safely used, but is a mixture
+ * time-wise where valid states were updated and invalid remained at the old
+ * value.
+ */
+int RecallStates(float statesForFusion[n_states], uint64_t msec);
+
+void ResetStoredStates();
+
+void quat2Tbn(Mat3f &Tbn, const float (&quat)[4]);
+
+void calcEarthRateNED(Vector3f &omega, float latitude);
+
+static void eul2quat(float (&quat)[4], const float (&eul)[3]);
+
+static void quat2eul(float (&eul)[3], const float (&quat)[4]);
+
+static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
+
+static void calcposNED(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+
+static void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+
+static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
+
+static float sq(float valIn);
+
+void OnGroundCheck();
+
+void CovarianceInit();
+
+void InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination);
+
+float ConstrainFloat(float val, float min, float max);
+
+void ConstrainVariances();
+
+void ConstrainStates();
+
+void ForceSymmetry();
+
+int CheckAndBound();
+
+void ResetPosition();
+
+void ResetVelocity();
+
+void ZeroVariables();
+
+void GetFilterState(struct ekf_status_report *state);
+
+void GetLastErrorState(struct ekf_status_report *last_error);
+
+bool StatesNaN(struct ekf_status_report *err_report);
+void FillErrorReport(struct ekf_status_report *err);
+
+void InitializeDynamic(float (&initvelNED)[3], float declination);
+
+protected:
+
+bool FilterHealthy();
+
+void ResetHeight(void);
+
+void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat);
+
+};
+
+uint32_t millis();
+
diff --git a/src/modules/ekf_att_pos_estimator/estimator.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index 5db1adbb3..768e0be35 100644
--- a/src/modules/ekf_att_pos_estimator/estimator.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -1,151 +1,126 @@
-#include "estimator.h"
+#include "estimator_23states.h"
#include <string.h>
-#include <stdarg.h>
-
-// Define EKF_DEBUG here to enable the debug print calls
-// if the macro is not set, these will be completely
-// optimized out by the compiler.
-//#define EKF_DEBUG
-
-#ifdef EKF_DEBUG
#include <stdio.h>
+#include <stdarg.h>
-static void
-ekf_debug_print(const char *fmt, va_list args)
-{
- fprintf(stderr, "%s: ", "[ekf]");
- vfprintf(stderr, fmt, args);
-
- fprintf(stderr, "\n");
-}
-
-static void
-ekf_debug(const char *fmt, ...)
-{
- va_list args;
-
- va_start(args, fmt);
- ekf_debug_print(fmt, args);
-}
-
-#else
-
-static void ekf_debug(const char *fmt, ...) { while(0){} }
-#endif
-
-float Vector3f::length(void) const
-{
- return sqrt(x*x + y*y + z*z);
-}
-
-void Vector3f::zero(void)
-{
- x = 0.0f;
- y = 0.0f;
- z = 0.0f;
-}
-
-Mat3f::Mat3f() {
- identity();
-}
-
-void Mat3f::identity() {
- 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;
-}
-
-AttPosEKF::AttPosEKF()
-
- /* NOTE: DO NOT initialize class members here. Use ZeroVariables()
- * instead to allow clean in-air re-initialization.
- */
+#define EKF_COVARIANCE_DIVERGED 1.0e8f
+
+AttPosEKF::AttPosEKF() :
+ covTimeStepMax(0.0f),
+ covDelAngMax(0.0f),
+ rngFinderPitch(0.0f),
+ a1(0.0f),
+ a2(0.0f),
+ a3(0.0f),
+ yawVarScale(0.0f),
+ windVelSigma(0.0f),
+ dAngBiasSigma(0.0f),
+ dVelBiasSigma(0.0f),
+ magEarthSigma(0.0f),
+ magBodySigma(0.0f),
+ gndHgtSigma(0.0f),
+ vneSigma(0.0f),
+ vdSigma(0.0f),
+ posNeSigma(0.0f),
+ posDSigma(0.0f),
+ magMeasurementSigma(0.0f),
+ airspeedMeasurementSigma(0.0f),
+ gyroProcessNoise(0.0f),
+ accelProcessNoise(0.0f),
+ EAS2TAS(1.0f),
+ magstate{},
+ resetMagState{},
+ KH{},
+ KHP{},
+ P{},
+ Kfusion{},
+ states{},
+ resetStates{},
+ storedStates{},
+ statetimeStamp{},
+ statesAtVelTime{},
+ statesAtPosTime{},
+ statesAtHgtTime{},
+ statesAtMagMeasTime{},
+ statesAtVtasMeasTime{},
+ statesAtRngTime{},
+ statesAtOptFlowTime{},
+ correctedDelAng(),
+ correctedDelVel(),
+ summedDelAng(),
+ summedDelVel(),
+ accNavMag(),
+ earthRateNED(),
+ angRate(),
+ lastGyroOffset(),
+ delAngTotal(),
+ Tbn(),
+ Tnb(),
+ accel(),
+ dVelIMU(),
+ dAngIMU(),
+ dtIMU(0),
+ fusionModeGPS(0),
+ innovVelPos{},
+ varInnovVelPos{},
+ velNED{},
+ accelGPSNED{},
+ posNE{},
+ hgtMea(0.0f),
+ baroHgtOffset(0.0f),
+ rngMea(0.0f),
+ innovMag{},
+ varInnovMag{},
+ magData{},
+ losData{},
+ innovVtas(0.0f),
+ innovRng(0.0f),
+ innovOptFlow{},
+ varInnovOptFlow{},
+ varInnovVtas(0.0f),
+ varInnovRng(0.0f),
+ VtasMeas(0.0f),
+ magDeclination(0.0f),
+ latRef(0.0f),
+ lonRef(-M_PI_F),
+ hgtRef(0.0f),
+ refSet(false),
+ magBias(),
+ covSkipCount(0),
+ gpsLat(0.0),
+ gpsLon(-M_PI),
+ gpsHgt(0.0f),
+ GPSstatus(0),
+ baroHgt(0.0f),
+ statesInitialised(false),
+ fuseVelData(false),
+ fusePosData(false),
+ fuseHgtData(false),
+ fuseMagData(false),
+ fuseVtasData(false),
+ fuseRngData(false),
+ fuseOptFlowData(false),
+
+ inhibitWindStates(true),
+ inhibitMagStates(true),
+ inhibitGndHgtState(true),
+
+ onGround(true),
+ staticMode(true),
+ useAirspeed(true),
+ useCompass(true),
+ useRangeFinder(false),
+ useOpticalFlow(false),
+
+ ekfDiverged(false),
+ lastReset(0),
+ current_ekf_state{},
+ last_ekf_error{},
+ numericalProtection(true),
+ storeIndex(0)
{
-
+ memset(&last_ekf_error, 0, sizeof(last_ekf_error));
+ memset(&current_ekf_state, 0, sizeof(current_ekf_state));
ZeroVariables();
InitialiseParameters();
}
@@ -171,7 +146,7 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
float qUpdated[4];
float quatMag;
float deltaQuat[4];
- const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS};
+ const Vector3f gravityNED(0.0f, 0.0f, GRAVITY_MSS);
// Remove sensor bias errors
correctedDelAng.x = dAngIMU.x - states[10];
@@ -181,6 +156,10 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
dVelIMU.y = dVelIMU.y;
dVelIMU.z = dVelIMU.z - states[13];
+ delAngTotal.x += correctedDelAng.x;
+ delAngTotal.y += correctedDelAng.y;
+ delAngTotal.z += correctedDelAng.z;
+
// Save current measurements
Vector3f prevDelAng = correctedDelAng;
@@ -199,8 +178,12 @@ void AttPosEKF::UpdateStrapdownEquationsNED()
}
else
{
- deltaQuat[0] = cosf(0.5f*rotationMag);
- float rotScaler = (sinf(0.5f*rotationMag))/rotationMag;
+ // We are using double here as we are unsure how small
+ // the angle differences are and if we get into numeric
+ // issues with float. The runtime impact is not measurable
+ // for these quantities.
+ deltaQuat[0] = cos(0.5*(double)rotationMag);
+ float rotScaler = (sin(0.5*(double)rotationMag))/(double)rotationMag;
deltaQuat[1] = correctedDelAng.x*rotScaler;
deltaQuat[2] = correctedDelAng.y*rotScaler;
deltaQuat[3] = correctedDelAng.z*rotScaler;
@@ -312,15 +295,28 @@ void AttPosEKF::CovariancePrediction(float dt)
float nextP[n_states][n_states];
// calculate covariance prediction process noise
- for (uint8_t i= 0; i<=9; i++) processNoise[i] = 1.0e-9f;
+ for (uint8_t i= 0; i<4; i++) processNoise[i] = 1.0e-9f;
+ for (uint8_t i= 4; i<10; i++) processNoise[i] = 1.0e-9f;
for (uint8_t i=10; i<=12; i++) processNoise[i] = dt * dAngBiasSigma;
// scale gyro bias noise when on ground to allow for faster bias estimation
for (uint8_t i=10; i<=12; i++) processNoise[i] = dt * dAngBiasSigma;
processNoise[13] = dVelBiasSigma;
- for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma;
- for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma;
- for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma;
- processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
+ if (!inhibitWindStates) {
+ for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma;
+ } else {
+ for (uint8_t i=14; i<=15; i++) processNoise[i] = 0;
+ }
+ if (!inhibitMagStates) {
+ for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma;
+ for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma;
+ } else {
+ for (uint8_t i=16; i<=21; i++) processNoise[i] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
+ } else {
+ processNoise[22] = 0;
+ }
// square all sigmas
for (unsigned i = 0; i < n_states; i++) processNoise[i] = sq(processNoise[i]);
@@ -932,30 +928,6 @@ void AttPosEKF::CovariancePrediction(float dt)
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,16,21);
- zeroCols(nextP,16,21);
- }
-
- // If on ground or not using airspeed sensing, inhibit wind velocity
- // covariance growth.
- if (onGround || !useAirspeed)
- {
- zeroRows(nextP,14,15);
- zeroCols(nextP,14,15);
- }
-
- // If on ground, inhibit terrain offset updates by
- // setting the coresponding covariance terms to zero.
- if (onGround)
- {
- zeroRows(nextP,22,22);
- zeroCols(nextP,22,22);
- }
-
// 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
@@ -972,57 +944,31 @@ void AttPosEKF::CovariancePrediction(float dt)
}
}
- if (onGround || staticMode) {
- // copy the portion of the variances we want to
- // propagate
- for (unsigned i = 0; i <= 13; i++) {
- P[i][i] = nextP[i][i];
-
- // force symmetry for observable states
- // force zero for non-observable states
- for (unsigned i = 1; i < n_states; i++)
- {
- for (uint8_t j = 0; j < i; j++)
- {
- if ((i > 13) || (j > 13)) {
- P[i][j] = 0.0f;
- } else {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- }
- P[j][i] = P[i][j];
- }
- }
- }
-
- } else {
-
- // Copy covariance
- for (unsigned i = 0; i < n_states; i++) {
- P[i][i] = nextP[i][i];
- }
+ // Copy covariance
+ for (unsigned i = 0; i < n_states; i++) {
+ P[i][i] = nextP[i][i];
+ }
- // force symmetry for observable states
- for (unsigned i = 1; i < n_states; i++)
+ // force symmetry for observable states
+ for (unsigned i = 1; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < i; j++)
{
- for (uint8_t j = 0; j < i; j++)
- {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- P[j][i] = P[i][j];
- }
+ P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
+ P[j][i] = P[i][j];
}
-
}
- ConstrainVariances();
+ ConstrainVariances();
}
void AttPosEKF::FuseVelposNED()
{
// declare variables used by fault isolation logic
- uint32_t gpsRetryTime = 30000; // time in msec before GPS fusion will be retried following innovation consistency failure
- uint32_t gpsRetryTimeNoTAS = 5000; // retry time if no TAS measurement available
- uint32_t hgtRetryTime = 5000; // height measurement retry time
+ uint32_t gpsRetryTime = 3000; // time in msec before GPS fusion will be retried following innovation consistency failure
+ uint32_t gpsRetryTimeNoTAS = 500; // retry time if no TAS measurement available
+ uint32_t hgtRetryTime = 500; // height measurement retry time
uint32_t horizRetryTime;
// declare variables used to check measurement errors
@@ -1034,7 +980,7 @@ void AttPosEKF::FuseVelposNED()
bool fuseData[6] = {false,false,false,false,false,false};
uint8_t stateIndex;
uint8_t obsIndex;
- uint8_t indexLimit;
+ uint8_t indexLimit = 22;
// declare variables used by state and covariance update calculations
float velErr;
@@ -1071,11 +1017,6 @@ void AttPosEKF::FuseVelposNED()
R_OBS[4] = R_OBS[3];
R_OBS[5] = sq(posDSigma) + sq(posErr);
- // 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)
{
@@ -1161,15 +1102,6 @@ void AttPosEKF::FuseVelposNED()
{
fuseData[5] = true;
}
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = 22;
- }
- else
- {
- indexLimit = 13;
- }
// Fuse measurements sequentially
for (obsIndex=0; obsIndex<=5; obsIndex++)
{
@@ -1178,7 +1110,7 @@ void AttPosEKF::FuseVelposNED()
stateIndex = 4 + obsIndex;
// Calculate the measurement innovation, using states from a
// different time coordinate if fusing height data
- if (obsIndex >= 0 && obsIndex <= 2)
+ if (obsIndex <= 2)
{
innovVelPos[obsIndex] = statesAtVelTime[stateIndex] - observation[obsIndex];
}
@@ -1193,7 +1125,7 @@ void AttPosEKF::FuseVelposNED()
// 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];
+ SK = 1.0/(double)varInnovVelPos[obsIndex];
for (uint8_t i= 0; i<=indexLimit; i++)
{
Kfusion[i] = P[i][stateIndex]*SK;
@@ -1203,6 +1135,22 @@ void AttPosEKF::FuseVelposNED()
if (obsIndex != 5) {
Kfusion[13] = 0;
}
+ // Don't update wind states if inhibited
+ if (inhibitWindStates) {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ // Don't update magnetic field states if inhibited
+ if (inhibitMagStates) {
+ for (uint8_t i = 16; i<=21; i++)
+ {
+ Kfusion[i] = 0;
+ }
+ }
+ // Don't update terrain state if inhibited
+ if (inhibitGndHgtState) {
+ Kfusion[22] = 0;
+ }
// Calculate state corrections and re-normalise the quaternions
for (uint8_t i = 0; i<=indexLimit; i++)
@@ -1269,7 +1217,6 @@ void AttPosEKF::FuseMagnetometer()
for (uint8_t i = 0; i < n_states; i++) {
H_MAG[i] = 0.0f;
}
- unsigned indexLimit;
// Perform sequential fusion of Magnetometer measurements.
// This assumes that the errors in the different components are
@@ -1277,23 +1224,10 @@ void AttPosEKF::FuseMagnetometer()
// 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))
+ if (useCompass && fuseMagData && (obsIndex < 3))
{
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = n_states;
- }
- else
- {
- indexLimit = 13 + 1;
- }
-
- // Sequential fusion of XYZ components to spread processing load across
- // three prediction time steps.
-
// Calculate observation jacobians and Kalman gains
- if (fuseMagData)
+ if (obsIndex == 0)
{
// Copy required states to local variable names
q0 = statesAtMagMeasTime[0];
@@ -1377,22 +1311,33 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MX[0]*(P[12][19] + 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][16]*SK_MX[1] + P[12][17]*SK_MX[5] - P[12][18]*SK_MX[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MX[0]*(P[13][19] + 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][16]*SK_MX[1] + P[13][17]*SK_MX[5] - P[13][18]*SK_MX[4]);
- Kfusion[14] = SK_MX[0]*(P[14][19] + 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][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]);
- Kfusion[15] = SK_MX[0]*(P[15][19] + 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][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]);
- Kfusion[16] = SK_MX[0]*(P[16][19] + 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][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]);
- Kfusion[17] = SK_MX[0]*(P[17][19] + 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][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]);
- Kfusion[18] = SK_MX[0]*(P[18][19] + 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][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]);
- Kfusion[19] = SK_MX[0]*(P[19][19] + 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][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]);
- Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]);
- Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]);
- Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MX[0]*(P[14][19] + 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][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]);
+ Kfusion[15] = SK_MX[0]*(P[15][19] + 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][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MX[0]*(P[16][19] + 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][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]);
+ Kfusion[17] = SK_MX[0]*(P[17][19] + 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][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]);
+ Kfusion[18] = SK_MX[0]*(P[18][19] + 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][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]);
+ Kfusion[19] = SK_MX[0]*(P[19][19] + 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][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]);
+ Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]);
+ Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]);
+ } else {
+ for (uint8_t i=16; i <= 21; i++) {
+ Kfusion[i] = 0;
+ }
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovMag[0] = 1.0f/SK_MX[0];
innovMag[0] = MagPred[0] - magData.x;
-
- // reset the observation index to 0 (we start by fusing the X
- // measurement)
- obsIndex = 0;
- fuseMagData = false;
}
else if (obsIndex == 1) // we are now fusing the Y measurement
{
@@ -1437,15 +1382,34 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MY[0]*(P[12][20] + 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][17]*SK_MY[1] - P[12][16]*SK_MY[3] + P[12][18]*SK_MY[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MY[0]*(P[13][20] + 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][17]*SK_MY[1] - P[13][16]*SK_MY[3] + P[13][18]*SK_MY[4]);
- Kfusion[14] = SK_MY[0]*(P[14][20] + 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][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]);
- Kfusion[15] = SK_MY[0]*(P[15][20] + 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][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]);
- Kfusion[16] = SK_MY[0]*(P[16][20] + 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][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]);
- Kfusion[17] = SK_MY[0]*(P[17][20] + 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][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]);
- Kfusion[18] = SK_MY[0]*(P[18][20] + 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][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]);
- Kfusion[19] = SK_MY[0]*(P[19][20] + 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][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]);
- Kfusion[20] = SK_MY[0]*(P[20][20] + 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][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]);
- Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]);
- Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MY[0]*(P[14][20] + 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][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]);
+ Kfusion[15] = SK_MY[0]*(P[15][20] + 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][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MY[0]*(P[16][20] + 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][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]);
+ Kfusion[17] = SK_MY[0]*(P[17][20] + 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][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]);
+ Kfusion[18] = SK_MY[0]*(P[18][20] + 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][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]);
+ Kfusion[19] = SK_MY[0]*(P[19][20] + 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][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]);
+ Kfusion[20] = SK_MY[0]*(P[20][20] + 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][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]);
+ Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]);
+ } else {
+ Kfusion[16] = 0;
+ Kfusion[17] = 0;
+ Kfusion[18] = 0;
+ Kfusion[19] = 0;
+ Kfusion[20] = 0;
+ Kfusion[21] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovMag[1] = 1.0f/SK_MY[0];
innovMag[1] = MagPred[1] - magData.y;
}
@@ -1493,31 +1457,50 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MZ[0]*(P[12][21] + 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][18]*SK_MZ[1] + P[12][16]*SK_MZ[5] - P[12][17]*SK_MZ[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MZ[0]*(P[13][21] + 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][18]*SK_MZ[1] + P[13][16]*SK_MZ[5] - P[13][17]*SK_MZ[4]);
- Kfusion[14] = SK_MZ[0]*(P[14][21] + 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][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]);
- Kfusion[15] = SK_MZ[0]*(P[15][21] + 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][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]);
- Kfusion[16] = SK_MZ[0]*(P[16][21] + 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][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]);
- Kfusion[17] = SK_MZ[0]*(P[17][21] + 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][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]);
- Kfusion[18] = SK_MZ[0]*(P[18][21] + 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][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]);
- Kfusion[19] = SK_MZ[0]*(P[19][21] + 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][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]);
- Kfusion[20] = SK_MZ[0]*(P[20][21] + 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][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]);
- Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]);
- Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MZ[0]*(P[14][21] + 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][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]);
+ Kfusion[15] = SK_MZ[0]*(P[15][21] + 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][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MZ[0]*(P[16][21] + 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][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]);
+ Kfusion[17] = SK_MZ[0]*(P[17][21] + 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][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]);
+ Kfusion[18] = SK_MZ[0]*(P[18][21] + 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][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]);
+ Kfusion[19] = SK_MZ[0]*(P[19][21] + 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][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]);
+ Kfusion[20] = SK_MZ[0]*(P[20][21] + 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][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]);
+ Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]);
+ } else {
+ Kfusion[16] = 0;
+ Kfusion[17] = 0;
+ Kfusion[18] = 0;
+ Kfusion[19] = 0;
+ Kfusion[20] = 0;
+ Kfusion[21] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
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)
+ if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0f)
{
// correct the state vector
- for (uint8_t j= 0; j < indexLimit; j++)
+ for (uint8_t j= 0; j < n_states; 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)
+ if (quatMag > 1e-12f)
{
for (uint8_t j= 0; j<=3; j++)
{
@@ -1528,7 +1511,7 @@ void AttPosEKF::FuseMagnetometer()
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in KH to reduce the
// number of operations
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
for (uint8_t j = 0; j <= 3; j++)
{
@@ -1550,9 +1533,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j < indexLimit; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
KHP[i][j] = 0.0f;
for (uint8_t k = 0; k <= 3; k++)
@@ -1569,9 +1552,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j < indexLimit; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
P[i][j] = P[i][j] - KHP[i][j];
}
@@ -1612,7 +1595,7 @@ void AttPosEKF::FuseAirspeed()
SH_TAS[0] = 1/(sqrt(sq(ve - vwe) + sq(vn - vwn) + sq(vd)));
SH_TAS[1] = (SH_TAS[0]*(2.0f*ve - 2*vwe))/2.0f;
SH_TAS[2] = (SH_TAS[0]*(2.0f*vn - 2*vwn))/2.0f;
-
+
float H_TAS[n_states];
for (uint8_t i = 0; i < n_states; i++) H_TAS[i] = 0.0f;
H_TAS[4] = SH_TAS[2];
@@ -1647,21 +1630,37 @@ void AttPosEKF::FuseAirspeed()
Kfusion[12] = SK_TAS*(P[12][4]*SH_TAS[2] - P[12][14]*SH_TAS[2] + P[12][5]*SH_TAS[1] - P[12][15]*SH_TAS[1] + P[12][6]*vd*SH_TAS[0]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_TAS*(P[13][4]*SH_TAS[2] - P[13][14]*SH_TAS[2] + P[13][5]*SH_TAS[1] - P[13][15]*SH_TAS[1] + P[13][6]*vd*SH_TAS[0]);
- Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
- Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
- Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
- Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
- Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
- Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
- Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
- Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]);
- Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
+ Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
+ Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
+ Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
+ Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
+ Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
+ Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]);
+ } else {
+ for (uint8_t i=16; i <= 21; i++) {
+ Kfusion[i] = 0;
+ }
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]);
+ } else {
+ Kfusion[22] = 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)
+ if ((innovVtas*innovVtas*SK_TAS) < 25.0f)
{
// correct the state vector
for (uint8_t j=0; j <= 22; j++)
@@ -1757,9 +1756,9 @@ void AttPosEKF::FuseRangeFinder()
float ptd = statesAtRngTime[22];
// Need to check that our range finder tilt angle is less than 30 degrees and we are using range finder data
- SH_RNG[4] = sin(rngFinderPitch);
- cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cos(rngFinderPitch);
- if (useRangeFinder && cosRngTilt > 0.87f)
+ SH_RNG[4] = sinf(rngFinderPitch);
+ cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cosf(rngFinderPitch);
+ if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f)
{
// Calculate observation jacobian and Kalman gain ignoring all states other than the terrain offset
// This prevents the range finder measurement modifying any of the other filter states and significantly reduces computations
@@ -1780,10 +1779,12 @@ void AttPosEKF::FuseRangeFinder()
SK_RNG[5] = SH_RNG[2];
Kfusion[22] = SK_RNG[0]*(P[22][9]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[22][0]*SH_RNG[1]*SK_RNG[2]*SK_RNG[5] - P[22][1]*SH_RNG[1]*SK_RNG[1]*SK_RNG[5] - P[22][2]*SH_RNG[1]*SK_RNG[4]*SK_RNG[5] + P[22][3]*SH_RNG[1]*SK_RNG[3]*SK_RNG[5]);
+ // Calculate the innovation variance for data logging
+ varInnovRng = 1.0f/SK_RNG[0];
+
// Calculate the measurement innovation
rngPred = (ptd - pd)/cosRngTilt;
innovRng = rngPred - rngMea;
- //printf("mea=%5.1f, pred=%5.1f, pd=%5.1f, ptd=%5.2f\n", rngMea, rngPred, pd, ptd);
// Check the innovation for consistency and don't fuse if > 5Sigma
if ((innovRng*innovRng*SK_RNG[0]) < 25)
@@ -1799,6 +1800,289 @@ void AttPosEKF::FuseRangeFinder()
}
+void AttPosEKF::FuseOptFlow()
+{
+ static uint8_t obsIndex;
+ static float SH_LOS[13];
+ static float SKK_LOS[15];
+ static float SK_LOS[2];
+ static float q0 = 0.0f;
+ static float q1 = 0.0f;
+ static float q2 = 0.0f;
+ static float q3 = 1.0f;
+ static float vn = 0.0f;
+ static float ve = 0.0f;
+ static float vd = 0.0f;
+ static float pd = 0.0f;
+ static float ptd = 0.0f;
+ static float R_LOS = 0.01f;
+ static float losPred[2];
+
+ // Transformation matrix from nav to body axes
+ Mat3f Tnb_local;
+ // Transformation matrix from body to sensor axes
+ // assume camera is aligned with Z body axis plus a misalignment
+ // defined by 3 small angles about X, Y and Z body axis
+ Mat3f Tbs;
+ Tbs.x.y = a3;
+ Tbs.y.x = -a3;
+ Tbs.x.z = -a2;
+ Tbs.z.x = a2;
+ Tbs.y.z = a1;
+ Tbs.z.y = -a1;
+ // Transformation matrix from navigation to sensor axes
+ Mat3f Tns;
+ float H_LOS[n_states];
+ for (uint8_t i = 0; i < n_states; i++) {
+ H_LOS[i] = 0.0f;
+ }
+ Vector3f velNED_local;
+ Vector3f relVelSensor;
+
+// Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg.
+ if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f)
+ {
+ // Sequential fusion of XY components to spread processing load across
+ // two prediction time steps.
+
+ // Calculate observation jacobians and Kalman gains
+ if (fuseOptFlowData)
+ {
+ // Copy required states to local variable names
+ q0 = statesAtOptFlowTime[0];
+ q1 = statesAtOptFlowTime[1];
+ q2 = statesAtOptFlowTime[2];
+ q3 = statesAtOptFlowTime[3];
+ vn = statesAtOptFlowTime[4];
+ ve = statesAtOptFlowTime[5];
+ vd = statesAtOptFlowTime[6];
+ pd = statesAtOptFlowTime[9];
+ ptd = statesAtOptFlowTime[22];
+ velNED_local.x = vn;
+ velNED_local.y = ve;
+ velNED_local.z = vd;
+
+ // calculate rotation from NED to body axes
+ float q00 = sq(q0);
+ float q11 = sq(q1);
+ float q22 = sq(q2);
+ float q33 = sq(q3);
+ float q01 = q0 * q1;
+ float q02 = q0 * q2;
+ float q03 = q0 * q3;
+ float q12 = q1 * q2;
+ float q13 = q1 * q3;
+ float q23 = q2 * q3;
+ Tnb_local.x.x = q00 + q11 - q22 - q33;
+ Tnb_local.y.y = q00 - q11 + q22 - q33;
+ Tnb_local.z.z = q00 - q11 - q22 + q33;
+ Tnb_local.y.x = 2*(q12 - q03);
+ Tnb_local.z.x = 2*(q13 + q02);
+ Tnb_local.x.y = 2*(q12 + q03);
+ Tnb_local.z.y = 2*(q23 - q01);
+ Tnb_local.x.z = 2*(q13 - q02);
+ Tnb_local.y.z = 2*(q23 + q01);
+
+ // calculate transformation from NED to sensor axes
+ Tns = Tbs*Tnb_local;
+
+ // calculate range from ground plain to centre of sensor fov assuming flat earth
+ float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f);
+
+ // calculate relative velocity in sensor frame
+ relVelSensor = Tns*velNED_local;
+
+ // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
+ losPred[0] = relVelSensor.y/range;
+ losPred[1] = -relVelSensor.x/range;
+
+ //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y);
+ //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y);
+ //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range);
+
+ // Calculate observation jacobians
+ SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
+ SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+ SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+ SH_LOS[3] = 1/(pd - ptd);
+ SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2;
+ SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3;
+ SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1;
+ SH_LOS[7] = 1/sq(pd - ptd);
+ SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1;
+ SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0;
+ SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3;
+ SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0;
+ SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2;
+
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+ H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+ H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+ H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3);
+ H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+ H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+ H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3));
+ H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3));
+ H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+ H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+
+ // Calculate Kalman gain
+ SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3);
+ SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3);
+ SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3);
+ SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3);
+ SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3);
+ SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3);
+ SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+ SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+ SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+ SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]);
+ SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+ SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+ SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+ SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]);
+ SKK_LOS[14] = SH_LOS[0];
+
+ SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]));
+ Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ varInnovOptFlow[0] = 1.0f/SK_LOS[0];
+ innovOptFlow[0] = losPred[0] - losData[0];
+
+ // reset the observation index to 0 (we start by fusing the X
+ // measurement)
+ obsIndex = 0;
+ fuseOptFlowData = false;
+ }
+ else if (obsIndex == 1) // we are now fusing the Y measurement
+ {
+ // Calculate observation jacobians
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+ H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+ H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+ H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+ H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1);
+ H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+ H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3));
+ H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3));
+ H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+ H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+
+ // Calculate Kalman gains
+ SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]));
+ Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ varInnovOptFlow[1] = 1.0f/SK_LOS[1];
+ innovOptFlow[1] = losPred[1] - losData[1];
+ }
+
+ // Check the innovation for consistency and don't fuse if > 3Sigma
+ if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f)
+ {
+ // correct the state vector
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex];
+ }
+ // normalise the quaternion states
+ float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12f)
+ {
+ for (uint8_t j= 0; j<=3; j++)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[j] = states[j] * quatMagInv;
+ }
+ }
+ // correct the covariance P = (I - K*H)*P
+ // take advantage of the empty columns in KH to reduce the
+ // number of operations
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j <= 6; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_LOS[j];
+ }
+ for (uint8_t j = 7; j <= 8; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ KH[i][9] = Kfusion[i] * H_LOS[9];
+ for (uint8_t j = 10; j <= 21; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ KH[i][22] = Kfusion[i] * H_LOS[22];
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ KHP[i][j] = 0.0f;
+ for (uint8_t k = 0; k <= 6; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
+ KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j];
+ }
+ }
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
+ obsIndex = obsIndex + 1;
+ ForceSymmetry();
+ ConstrainVariances();
+}
+
void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
{
uint8_t row;
@@ -1855,21 +2139,21 @@ int AttPosEKF::RecallStates(float* statesForFusion, uint64_t msec)
int64_t bestTimeDelta = 200;
unsigned bestStoreIndex = 0;
- for (unsigned storeIndex = 0; storeIndex < data_buffer_size; storeIndex++)
+ for (unsigned storeIndexLocal = 0; storeIndexLocal < data_buffer_size; storeIndexLocal++)
{
// Work around a GCC compiler bug - we know 64bit support on ARM is
// sketchy in GCC.
uint64_t timeDelta;
- if (msec > statetimeStamp[storeIndex]) {
- timeDelta = msec - statetimeStamp[storeIndex];
+ if (msec > statetimeStamp[storeIndexLocal]) {
+ timeDelta = msec - statetimeStamp[storeIndexLocal];
} else {
- timeDelta = statetimeStamp[storeIndex] - msec;
+ timeDelta = statetimeStamp[storeIndexLocal] - msec;
}
- if (timeDelta < bestTimeDelta)
+ if (timeDelta < (uint64_t)bestTimeDelta)
{
- bestStoreIndex = storeIndex;
+ bestStoreIndex = storeIndexLocal;
bestTimeDelta = timeDelta;
}
}
@@ -1926,7 +2210,7 @@ void AttPosEKF::quat2Tnb(Mat3f &Tnb, const float (&quat)[4])
Tnb.y.z = 2*(q23 + q01);
}
-void AttPosEKF::quat2Tbn(Mat3f &Tbn, const float (&quat)[4])
+void AttPosEKF::quat2Tbn(Mat3f &Tbn_ret, const float (&quat)[4])
{
// Calculate the body to nav cosine matrix
float q00 = sq(quat[0]);
@@ -1940,15 +2224,15 @@ void AttPosEKF::quat2Tbn(Mat3f &Tbn, const float (&quat)[4])
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);
+ Tbn_ret.x.x = q00 + q11 - q22 - q33;
+ Tbn_ret.y.y = q00 - q11 + q22 - q33;
+ Tbn_ret.z.z = q00 - q11 - q22 + q33;
+ Tbn_ret.x.y = 2*(q12 - q03);
+ Tbn_ret.x.z = 2*(q13 + q02);
+ Tbn_ret.y.x = 2*(q12 + q03);
+ Tbn_ret.y.z = 2*(q23 - q01);
+ Tbn_ret.z.x = 2*(q13 - q02);
+ Tbn_ret.z.y = 2*(q23 + q01);
}
void AttPosEKF::eul2quat(float (&quat)[4], const float (&eul)[3])
@@ -1979,26 +2263,44 @@ void AttPosEKF::calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd,
velNED[2] = gpsVelD;
}
-void AttPosEKF::calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef)
+void AttPosEKF::calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latReference, double lonReference, float hgtReference)
{
- posNED[0] = earthRadius * (lat - latRef);
- posNED[1] = earthRadius * cos(latRef) * (lon - lonRef);
- posNED[2] = -(hgt - hgtRef);
+ posNED[0] = earthRadius * (lat - latReference);
+ posNED[1] = earthRadius * cos(latReference) * (lon - lonReference);
+ posNED[2] = -(hgt - hgtReference);
}
-void AttPosEKF::calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef)
+void AttPosEKF::calcLLH(float posNED[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef)
{
- lat = latRef + posNED[0] * earthRadiusInv;
- lon = lonRef + posNED[1] * earthRadiusInv / cos(latRef);
+ lat = latRef + (double)posNED[0] * earthRadiusInv;
+ lon = lonRef + (double)posNED[1] * earthRadiusInv / cos(latRef);
hgt = hgtRef - posNED[2];
}
void AttPosEKF::OnGroundCheck()
{
- onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 6.0f));
+ onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f));
if (staticMode) {
staticMode = (!refSet || (GPSstatus < GPS_FIX_3D));
}
+ // don't update wind states if there is no airspeed measurement
+ if (onGround || !useAirspeed) {
+ inhibitWindStates = true;
+ } else {
+ inhibitWindStates =false;
+ }
+ // don't update magnetic field states if on ground or not using compass
+ if (onGround || !useCompass) {
+ inhibitMagStates = true;
+ } else {
+ inhibitMagStates = false;
+ }
+ // don't update terrain offset state if on ground
+ if (onGround) {
+ inhibitGndHgtState = true;
+ } else {
+ inhibitGndHgtState = false;
+ }
}
void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude)
@@ -2026,8 +2328,8 @@ void AttPosEKF::CovarianceInit()
P[11][11] = P[10][10];
P[12][12] = P[10][10];
P[13][13] = sq(0.2f*dtIMU);
- P[14][14] = sq(8.0f);
- P[15][14] = P[14][14];
+ P[14][14] = sq(0.0f);
+ P[15][15] = P[14][14];
P[16][16] = sq(0.02f);
P[17][17] = P[16][16];
P[18][18] = P[16][16];
@@ -2042,16 +2344,16 @@ float AttPosEKF::ConstrainFloat(float val, float min, float max)
float ret;
if (val > max) {
ret = max;
- ekf_debug("> max: %8.4f, val: %8.4f", max, val);
+ ekf_debug("> max: %8.4f, val: %8.4f", (double)max, (double)val);
} else if (val < min) {
ret = min;
- ekf_debug("< min: %8.4f, val: %8.4f", min, val);
+ ekf_debug("< min: %8.4f, val: %8.4f", (double)min, (double)val);
} else {
ret = val;
}
if (!isfinite(val)) {
- ekf_debug("constrain: non-finite!");
+ //ekf_debug("constrain: non-finite!");
}
return ret;
@@ -2194,10 +2496,71 @@ void AttPosEKF::ForceSymmetry()
{
P[i][j] = 0.5f * (P[i][j] + P[j][i]);
P[j][i] = P[i][j];
+
+ if ((fabsf(P[i][j]) > EKF_COVARIANCE_DIVERGED) ||
+ (fabsf(P[j][i]) > EKF_COVARIANCE_DIVERGED)) {
+ current_ekf_state.covariancesExcessive = true;
+ current_ekf_state.error |= true;
+ InitializeDynamic(velNED, magDeclination);
+ return;
+ }
+
+ float symmetric = 0.5f * (P[i][j] + P[j][i]);
+ P[i][j] = symmetric;
+ P[j][i] = symmetric;
}
}
}
+bool AttPosEKF::GyroOffsetsDiverged()
+{
+ // Detect divergence by looking for rapid changes of the gyro offset
+ Vector3f current_bias;
+ current_bias.x = states[10];
+ current_bias.y = states[11];
+ current_bias.z = states[12];
+
+ Vector3f delta = current_bias - lastGyroOffset;
+ float delta_len = delta.length();
+ float delta_len_scaled = 0.0f;
+
+ // Protect against division by zero
+ if (delta_len > 0.0f) {
+ float cov_mag = ConstrainFloat((P[10][10] + P[11][11] + P[12][12]), 1e-12f, 1e-8f);
+ delta_len_scaled = (5e-7 / (double)cov_mag) * (double)delta_len / (double)dtIMU;
+ }
+
+ bool diverged = (delta_len_scaled > 1.0f);
+ lastGyroOffset = current_bias;
+ current_ekf_state.error |= diverged;
+ current_ekf_state.gyroOffsetsExcessive = diverged;
+
+ return diverged;
+}
+
+bool AttPosEKF::VelNEDDiverged()
+{
+ Vector3f current_vel;
+ current_vel.x = states[4];
+ current_vel.y = states[5];
+ current_vel.z = states[6];
+
+ Vector3f gps_vel;
+ gps_vel.x = velNED[0];
+ gps_vel.y = velNED[1];
+ gps_vel.z = velNED[2];
+
+ Vector3f delta = current_vel - gps_vel;
+ float delta_len = delta.length();
+
+ bool excessive = (delta_len > 20.0f);
+
+ current_ekf_state.error |= excessive;
+ current_ekf_state.velOffsetExcessive = excessive;
+
+ return excessive;
+}
+
bool AttPosEKF::FilterHealthy()
{
if (!statesInitialised) {
@@ -2262,42 +2625,26 @@ void AttPosEKF::ResetVelocity(void)
}
}
-
-void AttPosEKF::FillErrorReport(struct ekf_status_report *err)
-{
- for (unsigned i = 0; i < n_states; i++)
- {
- err->states[i] = states[i];
- }
-
- err->velHealth = current_ekf_state.velHealth;
- err->posHealth = current_ekf_state.posHealth;
- err->hgtHealth = current_ekf_state.hgtHealth;
- err->velTimeout = current_ekf_state.velTimeout;
- err->posTimeout = current_ekf_state.posTimeout;
- err->hgtTimeout = current_ekf_state.hgtTimeout;
-}
-
-bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
+bool AttPosEKF::StatesNaN() {
bool err = false;
// check all integrators
if (!isfinite(summedDelAng.x) || !isfinite(summedDelAng.y) || !isfinite(summedDelAng.z)) {
- err_report->statesNaN = true;
+ current_ekf_state.angNaN = true;
ekf_debug("summedDelAng NaN: x: %f y: %f z: %f", (double)summedDelAng.x, (double)summedDelAng.y, (double)summedDelAng.z);
err = true;
goto out;
} // delta angles
if (!isfinite(correctedDelAng.x) || !isfinite(correctedDelAng.y) || !isfinite(correctedDelAng.z)) {
- err_report->statesNaN = true;
+ current_ekf_state.angNaN = true;
ekf_debug("correctedDelAng NaN: x: %f y: %f z: %f", (double)correctedDelAng.x, (double)correctedDelAng.y, (double)correctedDelAng.z);
err = true;
goto out;
} // delta angles
if (!isfinite(summedDelVel.x) || !isfinite(summedDelVel.y) || !isfinite(summedDelVel.z)) {
- err_report->statesNaN = true;
+ current_ekf_state.summedDelVelNaN = true;
ekf_debug("summedDelVel NaN: x: %f y: %f z: %f", (double)summedDelVel.x, (double)summedDelVel.y, (double)summedDelVel.z);
err = true;
goto out;
@@ -2308,7 +2655,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
for (unsigned j = 0; j < n_states; j++) {
if (!isfinite(KH[i][j])) {
- err_report->covarianceNaN = true;
+ current_ekf_state.KHNaN = true;
err = true;
ekf_debug("KH NaN");
goto out;
@@ -2316,7 +2663,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
if (!isfinite(KHP[i][j])) {
- err_report->covarianceNaN = true;
+ current_ekf_state.KHPNaN = true;
err = true;
ekf_debug("KHP NaN");
goto out;
@@ -2324,7 +2671,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
if (!isfinite(P[i][j])) {
- err_report->covarianceNaN = true;
+ current_ekf_state.covarianceNaN = true;
err = true;
ekf_debug("P NaN");
} // covariance matrix
@@ -2332,7 +2679,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
if (!isfinite(Kfusion[i])) {
- err_report->kalmanGainsNaN = true;
+ current_ekf_state.kalmanGainsNaN = true;
ekf_debug("Kfusion NaN");
err = true;
goto out;
@@ -2340,7 +2687,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
if (!isfinite(states[i])) {
- err_report->statesNaN = true;
+ current_ekf_state.statesNaN = true;
ekf_debug("states NaN: i: %u val: %f", i, (double)states[i]);
err = true;
goto out;
@@ -2349,7 +2696,7 @@ bool AttPosEKF::StatesNaN(struct ekf_status_report *err_report) {
out:
if (err) {
- FillErrorReport(err_report);
+ current_ekf_state.error |= true;
}
return err;
@@ -2365,47 +2712,105 @@ out:
* updated, but before any of the fusion steps are
* executed.
*/
-int AttPosEKF::CheckAndBound()
+int AttPosEKF::CheckAndBound(struct ekf_status_report *last_error)
{
// Store the old filter state
bool currStaticMode = staticMode;
+ // Limit reset rate to 5 Hz to allow the filter
+ // to settle
+ if (millis() - lastReset < 200) {
+ return 0;
+ }
+
+ if (ekfDiverged) {
+ ekfDiverged = false;
+ }
+
+ int ret = 0;
+
+ // Check if we're on ground - this also sets static mode.
+ OnGroundCheck();
+
// Reset the filter if the states went NaN
- if (StatesNaN(&last_ekf_error)) {
+ if (StatesNaN()) {
ekf_debug("re-initializing dynamic");
- InitializeDynamic(velNED, magDeclination);
+ // Reset and fill error report
+ InitializeDynamic(velNED, magDeclination);
- return 1;
+ ret = 1;
}
// Reset the filter if the IMU data is too old
if (dtIMU > 0.3f) {
+ current_ekf_state.imuTimeout = true;
+
+ // Fill error report
+ GetFilterState(&last_ekf_error);
+
ResetVelocity();
ResetPosition();
ResetHeight();
ResetStoredStates();
+ // Timeout cleared with this reset
+ current_ekf_state.imuTimeout = false;
+
// that's all we can do here, return
- return 2;
+ ret = 2;
}
- // Check if we're on ground - this also sets static mode.
- OnGroundCheck();
-
// Check if we switched between states
if (currStaticMode != staticMode) {
+ // Fill error report, but not setting error flag
+ GetFilterState(&last_ekf_error);
+
ResetVelocity();
ResetPosition();
ResetHeight();
ResetStoredStates();
- return 3;
+ ret = 3;
+ }
+
+ // Reset the filter if gyro offsets are excessive
+ if (GyroOffsetsDiverged()) {
+
+ // Reset and fill error report
+ InitializeDynamic(velNED, magDeclination);
+
+ // that's all we can do here, return
+ ret = 4;
+ }
+
+ // Reset the filter if it diverges too far from GPS
+ if (VelNEDDiverged()) {
+
+ // Reset and fill error report
+ InitializeDynamic(velNED, magDeclination);
+
+ // that's all we can do here, return
+ ret = 5;
+ }
+
+ // The excessive covariance detection already
+ // reset the filter. Just need to report here.
+ if (last_ekf_error.covariancesExcessive) {
+ ret = 6;
+ }
+
+ if (ret) {
+ ekfDiverged = true;
+ lastReset = millis();
+
+ // This reads the last error and clears it
+ GetLastErrorState(last_error);
}
- return 0;
+ return ret;
}
void AttPosEKF::AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat)
@@ -2456,6 +2861,36 @@ void AttPosEKF::AttitudeInit(float ax, float ay, float az, float mx, float my, f
void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
{
+ if (current_ekf_state.error) {
+ GetFilterState(&last_ekf_error);
+ }
+
+ ZeroVariables();
+
+ // Reset error states
+ current_ekf_state.error = false;
+ current_ekf_state.angNaN = false;
+ current_ekf_state.summedDelVelNaN = false;
+ current_ekf_state.KHNaN = false;
+ current_ekf_state.KHPNaN = false;
+ current_ekf_state.PNaN = false;
+ current_ekf_state.covarianceNaN = false;
+ current_ekf_state.kalmanGainsNaN = false;
+ current_ekf_state.statesNaN = false;
+
+ current_ekf_state.velHealth = true;
+ current_ekf_state.posHealth = true;
+ current_ekf_state.hgtHealth = true;
+
+ current_ekf_state.velTimeout = false;
+ current_ekf_state.posTimeout = false;
+ current_ekf_state.hgtTimeout = false;
+
+ fuseVelData = false;
+ fusePosData = false;
+ fuseHgtData = false;
+ fuseMagData = false;
+ fuseVtasData = false;
// Fill variables with valid data
velNED[0] = initvelNED[0];
@@ -2471,12 +2906,12 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
// Calculate initial Tbn matrix and rotate Mag measurements into NED
// to set initial NED magnetic field states
- Mat3f DCM;
- quat2Tbn(DCM, initQuat);
+ quat2Tbn(Tbn, initQuat);
+ Tnb = Tbn.transpose();
Vector3f initMagNED;
- 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;
+ initMagNED.x = Tbn.x.x*initMagXYZ.x + Tbn.x.y*initMagXYZ.y + Tbn.x.z*initMagXYZ.z;
+ initMagNED.y = Tbn.y.x*initMagXYZ.x + Tbn.y.y*initMagXYZ.y + Tbn.y.z*initMagXYZ.z;
+ initMagNED.z = Tbn.z.x*initMagXYZ.x + Tbn.z.y*initMagXYZ.y + Tbn.z.z*initMagXYZ.z;
magstate.q0 = initQuat[0];
magstate.q1 = initQuat[1];
@@ -2489,12 +2924,16 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
magstate.magYbias = magBias.y;
magstate.magZbias = magBias.z;
magstate.R_MAG = sq(magMeasurementSigma);
- magstate.DCM = DCM;
+ magstate.DCM = Tbn;
// write to state vector
for (uint8_t j=0; j<=3; j++) states[j] = initQuat[j]; // quaternions
for (uint8_t j=4; j<=6; j++) states[j] = initvelNED[j-4]; // velocities
- for (uint8_t j=7; j<=15; j++) states[j] = 0.0f; // positions, dAngBias, dVelBias, windVel
+ // positions:
+ states[7] = posNE[0];
+ states[8] = posNE[1];
+ states[9] = -hgtMea;
+ for (uint8_t j=10; j<=15; j++) states[j] = 0.0f; // dAngBias, dVelBias, windVel
states[16] = initMagNED.x; // Magnetic Field North
states[17] = initMagNED.y; // Magnetic Field East
states[18] = initMagNED.z; // Magnetic Field Down
@@ -2525,14 +2964,16 @@ void AttPosEKF::InitialiseFilter(float (&initvelNED)[3], double referenceLat, do
hgtRef = referenceHgt;
refSet = true;
- // we are at reference altitude, so measurement must be zero
- hgtMea = 0.0f;
+ // we are at reference position, so measurement must be zero
+ posNE[0] = 0.0f;
+ posNE[1] = 0.0f;
+
+ // we are at an unknown, possibly non-zero altitude - so altitude
+ // is not reset (hgtMea)
// the baro offset must be this difference now
baroHgtOffset = baroHgt - referenceHgt;
- memset(&last_ekf_error, 0, sizeof(last_ekf_error));
-
InitializeDynamic(initvelNED, declination);
}
@@ -2540,27 +2981,8 @@ void AttPosEKF::ZeroVariables()
{
// Initialize on-init initialized variables
- fusionModeGPS = 0;
- covSkipCount = 0;
- statesInitialised = false;
- fuseVelData = false;
- fusePosData = false;
- fuseHgtData = false;
- fuseMagData = false;
- fuseVtasData = false;
- onGround = true;
- staticMode = true;
- useAirspeed = true;
- useCompass = true;
- useRangeFinder = true;
- numericalProtection = true;
- refSet = false;
+
storeIndex = 0;
- gpsHgt = 0.0f;
- baroHgt = 0.0f;
- GPSstatus = 0;
- VtasMeas = 0.0f;
- magDeclination = 0.0f;
// Do the data structure init
for (unsigned i = 0; i < n_states; i++) {
@@ -2577,9 +2999,9 @@ void AttPosEKF::ZeroVariables()
correctedDelAng.zero();
summedDelAng.zero();
summedDelVel.zero();
-
dAngIMU.zero();
dVelIMU.zero();
+ lastGyroOffset.zero();
for (unsigned i = 0; i < data_buffer_size; i++) {
@@ -2598,12 +3020,27 @@ void AttPosEKF::ZeroVariables()
}
-void AttPosEKF::GetFilterState(struct ekf_status_report *state)
+void AttPosEKF::GetFilterState(struct ekf_status_report *err)
{
- memcpy(state, &current_ekf_state, sizeof(*state));
+
+ // Copy states
+ for (unsigned i = 0; i < n_states; i++) {
+ current_ekf_state.states[i] = states[i];
+ }
+ current_ekf_state.n_states = n_states;
+
+ memcpy(err, &current_ekf_state, sizeof(*err));
+
+ // err->velHealth = current_ekf_state.velHealth;
+ // err->posHealth = current_ekf_state.posHealth;
+ // err->hgtHealth = current_ekf_state.hgtHealth;
+ // err->velTimeout = current_ekf_state.velTimeout;
+ // err->posTimeout = current_ekf_state.posTimeout;
+ // err->hgtTimeout = current_ekf_state.hgtTimeout;
}
void AttPosEKF::GetLastErrorState(struct ekf_status_report *last_error)
{
memcpy(last_error, &last_ekf_error, sizeof(*last_error));
+ memset(&last_ekf_error, 0, sizeof(last_ekf_error));
}
diff --git a/src/modules/ekf_att_pos_estimator/estimator.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h
index e821089f2..faa6735ca 100644
--- a/src/modules/ekf_att_pos_estimator/estimator.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h
@@ -1,76 +1,10 @@
-#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;
- void zero(void);
-};
-
-class Mat3f
-{
-private:
-public:
- Vector3f x;
- Vector3f y;
- Vector3f z;
-
- Mat3f();
-
- void identity();
- 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);
+#include "estimator_utilities.h"
const unsigned int n_states = 23;
const unsigned int data_buffer_size = 50;
-enum GPS_FIX {
- GPS_FIX_NOFIX = 0,
- GPS_FIX_2D = 2,
- GPS_FIX_3D = 3
-};
-
-struct ekf_status_report {
- bool velHealth;
- bool posHealth;
- bool hgtHealth;
- bool velTimeout;
- bool posTimeout;
- bool hgtTimeout;
- uint32_t velFailTime;
- uint32_t posFailTime;
- uint32_t hgtFailTime;
- float states[n_states];
- bool statesNaN;
- bool covarianceNaN;
- bool kalmanGainsNaN;
-};
-
class AttPosEKF {
public:
@@ -95,6 +29,10 @@ public:
float covDelAngMax; // maximum delta angle between covariance predictions
float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
+ float a1; // optical flow sensor misalgnment angle about X axis (rad)
+ float a2; // optical flow sensor misalgnment angle about Y axis (rad)
+ float a3; // optical flow sensor misalgnment angle about Z axis (rad)
+
float yawVarScale;
float windVelSigma;
float dAngBiasSigma;
@@ -121,6 +59,9 @@ public:
covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
EAS2TAS = 1.0f;
+ a1 = 0.0f; // optical flow sensor misalgnment angle about X axis (rad)
+ a2 = 0.0f; // optical flow sensor misalgnment angle about Y axis (rad)
+ a3 = 0.0f; // optical flow sensor misalgnment angle about Z axis (rad)
yawVarScale = 1.0f;
windVelSigma = 0.1f;
@@ -141,7 +82,7 @@ public:
accelProcessNoise = 0.5f;
}
- struct {
+ struct mag_state_struct {
unsigned obsIndex;
float MagPred[3];
float SH_MAG[9];
@@ -157,7 +98,12 @@ public:
float magZbias;
float R_MAG;
Mat3f DCM;
- } magstate;
+ };
+
+ struct mag_state_struct magstate;
+ struct mag_state_struct resetMagState;
+
+
// Global variables
@@ -166,6 +112,7 @@ public:
float P[n_states][n_states]; // covariance matrix
float Kfusion[n_states]; // Kalman gains
float states[n_states]; // state matrix
+ float resetStates[n_states];
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
@@ -175,6 +122,7 @@ public:
float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
float statesAtRngTime[n_states]; // filter states at the effective measurement time
+ float statesAtOptFlowTime[n_states]; // States at the effective optical flow measurement time
Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
@@ -183,6 +131,8 @@ public:
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 lastGyroOffset; // Last gyro offset
+ Vector3f delAngTotal;
Mat3f Tbn; // transformation matrix from body to NED coordinates
Mat3f Tnb; // transformation amtrix from NED to body coordinates
@@ -196,18 +146,22 @@ public:
float varInnovVelPos[6]; // innovation variance output
float velNED[3]; // North, East, Down velocity obs (m/s)
+ float accelGPSNED[3]; // Acceleration predicted by GPS in earth frame
float posNE[2]; // North, East position obs (m)
float hgtMea; // measured height (m)
float baroHgtOffset; ///< the baro (weather) offset from normalized altitude
float rngMea; // Ground distance
- float posNED[3]; // North, East Down position (m)
float innovMag[3]; // innovation output
float varInnovMag[3]; // innovation variance output
Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
+ float losData[2]; // optical flow LOS rate measurements (rad/sec)
float innovVtas; // innovation output
float innovRng; ///< Range finder innovation
+ float innovOptFlow[2]; // optical flow LOS innovations (rad/sec)
+ float varInnovOptFlow[2]; // optical flow innovations variances (rad/sec)^2
float varInnovVtas; // innovation variance output
+ float varInnovRng; // range finder innovation variance
float VtasMeas; // true airspeed measurement (m/s)
float magDeclination; ///< magnetic declination
double latRef; // WGS-84 latitude of reference point (rad)
@@ -218,8 +172,6 @@ public:
unsigned covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction
// GPS input data variables
- float gpsCourse;
- float gpsVelD;
double gpsLat;
double gpsLon;
float gpsHgt;
@@ -236,12 +188,21 @@ public:
bool fuseMagData; // boolean true when magnetometer data is to be fused
bool fuseVtasData; // boolean true when airspeed data is to be fused
bool fuseRngData; ///< true when range data is fused
+ bool fuseOptFlowData; // true when optical flow data is fused
+
+ bool inhibitWindStates; // true when wind states and covariances are to remain constant
+ bool inhibitMagStates; // true when magnetic field states and covariances are to remain constant
+ bool inhibitGndHgtState; // true when the terrain ground height offset state and covariances are to remain constant
bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
bool staticMode; ///< boolean true if no position feedback is fused
bool useAirspeed; ///< boolean true if airspeed data is being used
bool useCompass; ///< boolean true if magnetometer data is being used
bool useRangeFinder; ///< true when rangefinder is being used
+ bool useOpticalFlow; // true when optical flow data is being used
+
+ bool ekfDiverged;
+ uint64_t lastReset;
struct ekf_status_report current_ekf_state;
struct ekf_status_report last_ekf_error;
@@ -263,7 +224,7 @@ void FuseAirspeed();
void FuseRangeFinder();
-void FuseOpticalFlow();
+void FuseOptFlow();
void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
@@ -289,7 +250,7 @@ int RecallStates(float *statesForFusion, uint64_t msec);
void ResetStoredStates();
-void quat2Tbn(Mat3f &Tbn, const float (&quat)[4]);
+void quat2Tbn(Mat3f &TBodyNed, const float (&quat)[4]);
void calcEarthRateNED(Vector3f &omega, float latitude);
@@ -299,9 +260,9 @@ static void quat2eul(float (&eul)[3], const float (&quat)[4]);
static void calcvelNED(float (&velNED)[3], float gpsCourse, float gpsGndSpd, float gpsVelD);
-static void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
+void calcposNED(float (&posNED)[3], double lat, double lon, float hgt, double latRef, double lonRef, float hgtRef);
-static void calcLLH(float (&posNED)[3], float lat, float lon, float hgt, float latRef, float lonRef, float hgtRef);
+static void calcLLH(float posNED[3], double &lat, double &lon, float &hgt, double latRef, double lonRef, float hgtRef);
static void quat2Tnb(Mat3f &Tnb, const float (&quat)[4]);
@@ -321,7 +282,7 @@ void ConstrainStates();
void ForceSymmetry();
-int CheckAndBound();
+int CheckAndBound(struct ekf_status_report *last_error);
void ResetPosition();
@@ -333,8 +294,7 @@ void GetFilterState(struct ekf_status_report *state);
void GetLastErrorState(struct ekf_status_report *last_error);
-bool StatesNaN(struct ekf_status_report *err_report);
-void FillErrorReport(struct ekf_status_report *err);
+bool StatesNaN();
void InitializeDynamic(float (&initvelNED)[3], float declination);
@@ -342,6 +302,10 @@ protected:
bool FilterHealthy();
+bool GyroOffsetsDiverged();
+
+bool VelNEDDiverged();
+
void ResetHeight(void);
void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat);
diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
new file mode 100644
index 000000000..77cc1eeeb
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
@@ -0,0 +1,162 @@
+
+#include "estimator_utilities.h"
+
+// Define EKF_DEBUG here to enable the debug print calls
+// if the macro is not set, these will be completely
+// optimized out by the compiler.
+//#define EKF_DEBUG
+
+#ifdef EKF_DEBUG
+#include <stdio.h>
+#include <stdarg.h>
+
+static void
+ekf_debug_print(const char *fmt, va_list args)
+{
+ fprintf(stderr, "%s: ", "[ekf]");
+ vfprintf(stderr, fmt, args);
+
+ fprintf(stderr, "\n");
+}
+
+void
+ekf_debug(const char *fmt, ...)
+{
+ va_list args;
+
+ va_start(args, fmt);
+ ekf_debug_print(fmt, args);
+}
+
+#else
+
+void ekf_debug(const char *fmt, ...) { while(0){} }
+#endif
+
+float Vector3f::length(void) const
+{
+ return sqrt(x*x + y*y + z*z);
+}
+
+void Vector3f::zero(void)
+{
+ x = 0.0f;
+ y = 0.0f;
+ z = 0.0f;
+}
+
+Mat3f::Mat3f() :
+ x{1.0f, 0.0f, 0.0f},
+ y{0.0f, 1.0f, 0.0f},
+ z{0.0f, 0.0f, 1.0f}
+{
+}
+
+void Mat3f::identity() {
+ 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 matrix product
+Mat3f operator*( Mat3f matIn1, Mat3f matIn2)
+{
+ Mat3f matOut;
+ matOut.x.x = matIn1.x.x*matIn2.x.x + matIn1.x.y*matIn2.y.x + matIn1.x.z*matIn2.z.x;
+ matOut.x.y = matIn1.x.x*matIn2.x.y + matIn1.x.y*matIn2.y.y + matIn1.x.z*matIn2.z.y;
+ matOut.x.z = matIn1.x.x*matIn2.x.z + matIn1.x.y*matIn2.y.z + matIn1.x.z*matIn2.z.z;
+
+ matOut.y.x = matIn1.y.x*matIn2.x.x + matIn1.y.y*matIn2.y.x + matIn1.y.z*matIn2.z.x;
+ matOut.y.y = matIn1.y.x*matIn2.x.y + matIn1.y.y*matIn2.y.y + matIn1.y.z*matIn2.z.y;
+ matOut.y.z = matIn1.y.x*matIn2.x.z + matIn1.y.y*matIn2.y.z + matIn1.y.z*matIn2.z.z;
+
+ matOut.z.x = matIn1.z.x*matIn2.x.x + matIn1.z.y*matIn2.y.x + matIn1.z.z*matIn2.z.x;
+ matOut.z.y = matIn1.z.x*matIn2.x.y + matIn1.z.y*matIn2.y.y + matIn1.z.z*matIn2.z.y;
+ matOut.z.z = matIn1.z.x*matIn2.x.z + matIn1.z.y*matIn2.y.z + matIn1.z.z*matIn2.z.z;
+
+ return matOut;
+}
+
+// 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;
+}
diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h
new file mode 100644
index 000000000..6d1f47b68
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h
@@ -0,0 +1,89 @@
+#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.0
+#define earthRadiusInv 1.5678540e-7
+
+class Vector3f
+{
+private:
+public:
+ float x;
+ float y;
+ float z;
+
+ Vector3f(float a=0.0f, float b=0.0f, float c=0.0f) :
+ x(a),
+ y(b),
+ z(c)
+ {}
+
+ float length(void) const;
+ void zero(void);
+};
+
+class Mat3f
+{
+private:
+public:
+ Vector3f x;
+ Vector3f y;
+ Vector3f z;
+
+ Mat3f();
+
+ void identity();
+ 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);
+Mat3f operator*( Mat3f matIn1, Mat3f matIn2);
+Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2);
+Vector3f operator*(Vector3f vecIn1, float sclIn1);
+
+void swap_var(float &d1, float &d2);
+
+enum GPS_FIX {
+ GPS_FIX_NOFIX = 0,
+ GPS_FIX_2D = 2,
+ GPS_FIX_3D = 3
+};
+
+struct ekf_status_report {
+ bool error;
+ bool velHealth;
+ bool posHealth;
+ bool hgtHealth;
+ bool velTimeout;
+ bool posTimeout;
+ bool hgtTimeout;
+ bool imuTimeout;
+ uint32_t velFailTime;
+ uint32_t posFailTime;
+ uint32_t hgtFailTime;
+ float states[32];
+ unsigned n_states;
+ bool angNaN;
+ bool summedDelVelNaN;
+ bool KHNaN;
+ bool KHPNaN;
+ bool PNaN;
+ bool covarianceNaN;
+ bool kalmanGainsNaN;
+ bool statesNaN;
+ bool gyroOffsetsExcessive;
+ bool covariancesExcessive;
+ bool velOffsetExcessive;
+};
+
+void ekf_debug(const char *fmt, ...);
diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index 6fefec2c2..36d854ddd 100644
--- a/src/modules/ekf_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -39,4 +39,7 @@ MODULE_COMMAND = ekf_att_pos_estimator
SRCS = ekf_att_pos_estimator_main.cpp \
ekf_att_pos_estimator_params.c \
- estimator.cpp
+ estimator_23states.cpp \
+ estimator_utilities.cpp
+
+EXTRACXXFLAGS = -Weffc++
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index c026e29a7..0cea13cc4 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * 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
@@ -99,13 +98,21 @@ public:
/**
* Start the sensors task.
*
- * @return OK on success.
+ * @return OK on success.
*/
int start();
+ /**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
private:
bool _task_should_exit; /**< if true, sensor task should exit */
+ bool _task_running; /**< if true, task is running in its mainloop */
int _control_task; /**< task handle for sensor task */
int _att_sub; /**< vehicle attitude subscription */
@@ -276,6 +283,7 @@ private:
* Main sensor collection task.
*/
void task_main();
+
};
namespace att_control
@@ -287,12 +295,13 @@ namespace att_control
#endif
static const int ERROR = -1;
-FixedwingAttitudeControl *g_control;
+FixedwingAttitudeControl *g_control = nullptr;
}
FixedwingAttitudeControl::FixedwingAttitudeControl() :
_task_should_exit(false),
+ _task_running(false),
_control_task(-1),
/* subscriptions */
@@ -598,6 +607,8 @@ FixedwingAttitudeControl::task_main()
fds[1].fd = _att_sub;
fds[1].events = POLLIN;
+ _task_running = true;
+
while (!_task_should_exit) {
static int loop_counter = 0;
@@ -707,14 +718,21 @@ FixedwingAttitudeControl::task_main()
float throttle_sp = 0.0f;
if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) {
+ /* read in attitude setpoint from attitude setpoint uorb topic */
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
throttle_sp = _att_sp.thrust;
/* reset integrals where needed */
- if (_att_sp.roll_reset_integral)
+ if (_att_sp.roll_reset_integral) {
_roll_ctrl.reset_integrator();
-
+ }
+ if (_att_sp.pitch_reset_integral) {
+ _pitch_ctrl.reset_integrator();
+ }
+ if (_att_sp.yaw_reset_integral) {
+ _yaw_ctrl.reset_integrator();
+ }
} else {
/*
* Scale down roll and pitch as the setpoints are radians
@@ -914,6 +932,7 @@ FixedwingAttitudeControl::task_main()
warnx("exiting.\n");
_control_task = -1;
+ _task_running = false;
_exit(0);
}
@@ -959,6 +978,14 @@ int fw_att_control_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (att_control::g_control == nullptr || !att_control::g_control->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}
diff --git a/src/modules/fw_att_control/module.mk b/src/modules/fw_att_control/module.mk
index 1e600757e..89c6494c5 100644
--- a/src/modules/fw_att_control/module.mk
+++ b/src/modules/fw_att_control/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = fw_att_control
SRCS = fw_att_control_main.cpp \
fw_att_control_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 116d3cc63..08c996ebc 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier
+ * 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
@@ -43,8 +42,8 @@
* Proceedings of the AIAA Guidance, Navigation and Control
* Conference, Aug 2004. AIAA-2004-4900.
*
- * Original implementation for total energy control class:
- * Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl)
+ * Implementation for total energy control class:
+ * Thomas Gubler
*
* More details and acknowledgements in the referenced library headers.
*
@@ -88,9 +87,9 @@
#include <mavlink/mavlink_log.h>
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
-#include <external_lgpl/tecs/tecs.h>
#include <drivers/drv_range_finder.h>
#include "landingslope.h"
+#include "mtecs/mTecs.h"
/**
@@ -120,10 +119,18 @@ public:
*/
int start();
+ /**
+ * Task status
+ *
+ * @return true if the mainloop is running
+ */
+ bool task_running() { return _task_running; }
+
private:
int _mavlink_fd;
bool _task_should_exit; /**< if true, sensor task should exit */
+ bool _task_running; /**< if true, task is running in its mainloop */
int _control_task; /**< task handle for sensor task */
int _global_pos_sub;
@@ -153,8 +160,6 @@ private:
perf_counter_t _loop_perf; /**< loop performance counter */
- bool _setpoint_valid; /**< flag if the position control setpoint is valid */
-
/** manual control states */
float _altctrl_hold_heading; /**< heading the system should hold in altctrl mode */
double _loiter_hold_lat;
@@ -200,7 +205,8 @@ private:
math::Matrix<3, 3> _R_nb; ///< current attitude
ECL_L1_Pos_Controller _l1_control;
- TECS _tecs;
+ fwPosctrl::mTecs _mTecs;
+ bool _was_pos_control_mode;
struct {
float l1_period;
@@ -343,11 +349,11 @@ private:
/**
* Control position.
*/
- bool control_position(const math::Vector<2> &global_pos, const math::Vector<2> &ground_speed,
+ bool control_position(const math::Vector<2> &global_pos, const math::Vector<3> &ground_speed,
const struct position_setpoint_triplet_s &_pos_sp_triplet);
float calculate_target_airspeed(float airspeed_demand);
- void calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet);
+ void calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed_2d, const struct position_setpoint_triplet_s &pos_sp_triplet);
/**
* Shim for calling task_main from task_create.
@@ -368,6 +374,19 @@ private:
* Reset landing state
*/
void reset_landing_state();
+
+ /*
+ * Call TECS : a wrapper function to call one of the TECS implementations (mTECS is called only if enabled via parameter)
+ * XXX need to clean up/remove this function once mtecs fully replaces TECS
+ */
+ void tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
+ float pitch_min_rad, float pitch_max_rad,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ bool climbout_mode, float climbout_pitch_min_rad,
+ float altitude,
+ const math::Vector<3> &ground_speed,
+ tecs_mode mode = TECS_MODE_NORMAL);
+
};
namespace l1_control
@@ -379,13 +398,14 @@ namespace l1_control
#endif
static const int ERROR = -1;
-FixedwingPositionControl *g_control;
+FixedwingPositionControl *g_control = nullptr;
}
FixedwingPositionControl::FixedwingPositionControl() :
_mavlink_fd(-1),
_task_should_exit(false),
+ _task_running(false),
_control_task(-1),
/* subscriptions */
@@ -402,11 +422,21 @@ FixedwingPositionControl::FixedwingPositionControl() :
_attitude_sp_pub(-1),
_nav_capabilities_pub(-1),
+ _att(),
+ _att_sp(),
+ _nav_capabilities(),
+ _manual(),
+ _airspeed(),
+ _control_mode(),
+ _global_pos(),
+ _pos_sp_triplet(),
+ _sensor_combined(),
+ _range_finder(),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
/* states */
- _setpoint_valid(false),
_loiter_hold(false),
land_noreturn_horizontal(false),
land_noreturn_vertical(false),
@@ -422,16 +452,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
_airspeed_valid(false),
_groundspeed_undershoot(0.0f),
_global_pos_valid(false),
- _att(),
- _att_sp(),
- _nav_capabilities(),
- _manual(),
- _airspeed(),
- _control_mode(),
- _global_pos(),
- _pos_sp_triplet(),
- _sensor_combined(),
- _range_finder()
+ _mTecs(),
+ _was_pos_control_mode(false)
{
_nav_capabilities.turn_distance = 0.0f;
@@ -550,23 +572,6 @@ FixedwingPositionControl::parameters_update()
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
- _tecs.set_time_const(_parameters.time_const);
- _tecs.set_min_sink_rate(_parameters.min_sink_rate);
- _tecs.set_max_sink_rate(_parameters.max_sink_rate);
- _tecs.set_throttle_damp(_parameters.throttle_damp);
- _tecs.set_integrator_gain(_parameters.integrator_gain);
- _tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit);
- _tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega);
- _tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega);
- _tecs.set_roll_throttle_compensation(_parameters.roll_throttle_compensation);
- _tecs.set_speed_weight(_parameters.speed_weight);
- _tecs.set_pitch_damping(_parameters.pitch_damping);
- _tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
- _tecs.set_indicated_airspeed_max(_parameters.airspeed_max);
- _tecs.set_max_climb_rate(_parameters.max_climb_rate);
- _tecs.set_heightrate_p(_parameters.heightrate_p);
- _tecs.set_speedrate_p(_parameters.speedrate_p);
-
/* sanity check parameters */
if (_parameters.airspeed_max < _parameters.airspeed_min ||
_parameters.airspeed_max < 5.0f ||
@@ -589,6 +594,9 @@ FixedwingPositionControl::parameters_update()
/* Update Launch Detector Parameters */
launchDetector.updateParams();
+ /* Update the mTecs */
+ _mTecs.updateParams();
+
return OK;
}
@@ -635,9 +643,6 @@ FixedwingPositionControl::vehicle_airspeed_poll()
}
}
- /* update TECS state */
- _tecs.enable_airspeed(_airspeed_valid);
-
return airspeed_updated;
}
@@ -692,7 +697,6 @@ FixedwingPositionControl::vehicle_setpoint_poll()
if (pos_sp_triplet_updated) {
orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
- _setpoint_valid = true;
}
}
@@ -734,15 +738,15 @@ FixedwingPositionControl::calculate_target_airspeed(float airspeed_demand)
}
void
-FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed, const struct position_setpoint_triplet_s &pos_sp_triplet)
+FixedwingPositionControl::calculate_gndspeed_undershoot(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed_2d, const struct position_setpoint_triplet_s &pos_sp_triplet)
{
- if (_global_pos_valid && !(pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER)) {
+ if (pos_sp_triplet.current.valid && !(pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER)) {
/* rotate ground speed vector with current attitude */
math::Vector<2> yaw_vector(_R_nb(0, 0), _R_nb(1, 0));
yaw_vector.normalize();
- float ground_speed_body = yaw_vector * ground_speed;
+ float ground_speed_body = yaw_vector * ground_speed_2d;
/* The minimum desired ground speed is the minimum airspeed projected on to the ground using the altitude and horizontal difference between the waypoints if available*/
float distance = 0.0f;
@@ -801,23 +805,19 @@ float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt,
}
bool
-FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed,
+FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<3> &ground_speed,
const struct position_setpoint_triplet_s &pos_sp_triplet)
{
bool setpoint = true;
- calculate_gndspeed_undershoot(current_position, ground_speed, pos_sp_triplet);
+ math::Vector<2> ground_speed_2d = {ground_speed(0), ground_speed(1)};
+ calculate_gndspeed_undershoot(current_position, ground_speed_2d, pos_sp_triplet);
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
- // XXX re-visit
- float baro_altitude = _global_pos.alt;
-
/* filter speed and altitude for controller */
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
- math::Vector<3> accel_earth = _R_nb * accel_body;
- _tecs.update_50hz(baro_altitude, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth);
float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt;
/* no throttle limit as default */
@@ -827,20 +827,31 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// XXX this should only execute if auto AND safety off (actuators active),
// else integrators should be constantly reset.
- if (_control_mode.flag_control_position_enabled) {
+ if (pos_sp_triplet.current.valid) {
+
+ if (!_was_pos_control_mode) {
+ /* reset integrators */
+ if (_mTecs.getEnabled()) {
+ _mTecs.resetIntegrators();
+ _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s);
+ }
+ }
+
+ _was_pos_control_mode = true;
/* get circle mode */
bool was_circle_mode = _l1_control.circle_mode();
- /* restore speed weight, in case changed intermittently (e.g. in landing handling) */
- _tecs.set_speed_weight(_parameters.speed_weight);
-
/* current waypoint (the one currently heading for) */
math::Vector<2> next_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
/* current waypoint (the one currently heading for) */
math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon);
+ /* Initialize attitude controller integrator reset flags to 0 */
+ _att_sp.roll_reset_integral = false;
+ _att_sp.pitch_reset_integral = false;
+ _att_sp.yaw_reset_integral = false;
/* previous waypoint */
math::Vector<2> prev_wp;
@@ -859,31 +870,29 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
- if (pos_sp_triplet.current.type == SETPOINT_TYPE_NORMAL) {
+ if (pos_sp_triplet.current.type == SETPOINT_TYPE_POSITION) {
/* waypoint is a plain navigation waypoint */
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim), eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed);
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LOITER) {
/* waypoint is a loiter waypoint */
_l1_control.navigate_loiter(curr_wp, current_position, pos_sp_triplet.current.loiter_radius,
- pos_sp_triplet.current.loiter_direction, ground_speed);
+ pos_sp_triplet.current.loiter_direction, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim), eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed);
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) {
@@ -908,7 +917,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// warnx("NORET: %d, target_bearing: %d, yaw: %d", (int)land_noreturn_horizontal, (int)math::degrees(target_bearing), (int)math::degrees(_att.yaw));
- _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(target_bearing, _att.yaw, ground_speed_2d);
/* limit roll motion to prevent wings from touching the ground first */
_att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-10.0f), math::radians(10.0f));
@@ -918,7 +927,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else {
/* normal navigation */
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
}
_att_sp.roll_body = _l1_control.nav_roll();
@@ -940,9 +949,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
float airspeed_land = 1.3f * _parameters.airspeed_min;
float airspeed_approach = 1.3f * _parameters.airspeed_min;
- /* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
- float L_altitude_rel = landingslope.getLandingSlopeRelativeAltitude(L_wp_distance);
+ /* Calculate altitude of last ordinary waypoint L */
+ float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
@@ -977,11 +985,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
land_stayonground = true;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + flare_curve_alt_rel, calculate_target_airspeed(airspeed_land),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, flare_pitch_angle_rad,
- 0.0f, throttle_max, throttle_land,
- flare_pitch_angle_rad, math::radians(15.0f));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + flare_curve_alt_rel,
+ calculate_target_airspeed(airspeed_land), eas2tas,
+ flare_pitch_angle_rad, math::radians(15.0f),
+ 0.0f, throttle_max, throttle_land,
+ false, flare_pitch_angle_rad,
+ _pos_sp_triplet.current.alt + relative_alt, ground_speed,
+ land_motor_lim ? TECS_MODE_LAND_THROTTLELIM : TECS_MODE_LAND);
if (!land_noreturn_vertical) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, flaring");
@@ -994,11 +1004,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* intersect glide slope:
* minimize speed to approach speed
- * if current position is higher or within 10m of slope follow the glide slope
- * if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope
+ * if current position is higher than the slope follow the glide slope (sink to the
+ * glide slope)
+ * also if the system captures the slope it should stay
+ * on the slope (bool land_onslope)
+ * if current position is below the slope continue at previous wp altitude
+ * until the intersection with slope
* */
float altitude_desired_rel = relative_alt;
- if (relative_alt > landing_slope_alt_rel_desired - 10.0f) {
+ if (relative_alt > landing_slope_alt_rel_desired || land_onslope) {
/* stay on slope */
altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
@@ -1007,28 +1021,40 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
} else {
/* continue horizontally */
- altitude_desired_rel = math::max(relative_alt, L_altitude_rel);
+ altitude_desired_rel = _pos_sp_triplet.previous.valid ? L_altitude_rel : relative_alt;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + altitude_desired_rel, calculate_target_airspeed(airspeed_approach),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt + altitude_desired_rel,
+ calculate_target_airspeed(airspeed_approach), eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _pos_sp_triplet.current.alt + relative_alt,
+ ground_speed);
}
} else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) {
/* Perform launch detection */
-// warnx("Launch detection running");
if(!launch_detected) { //do not do further checks once a launch was detected
if (launchDetector.launchDetectionEnabled()) {
static hrt_abstime last_sent = 0;
if(hrt_absolute_time() - last_sent > 4e6) {
-// warnx("Launch detection running");
mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running");
last_sent = hrt_absolute_time();
}
+
+ /* Tell the attitude controller to stop integrating while we are waiting
+ * for the launch */
+ _att_sp.roll_reset_integral = true;
+ _att_sp.pitch_reset_integral = true;
+ _att_sp.yaw_reset_integral = true;
+
+ /* Detect launch */
launchDetector.update(_sensor_combined.accelerometer_m_s2[0]);
if (launchDetector.getLaunchDetected()) {
launch_detected = true;
@@ -1041,7 +1067,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
- _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed);
+ _l1_control.navigate_waypoints(prev_wp, curr_wp, current_position, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
@@ -1052,22 +1078,36 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
if (altitude_error > 15.0f) {
/* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(1.3f * _parameters.airspeed_min),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- true, math::max(math::radians(pos_sp_triplet.current.pitch_min), math::radians(10.0f)),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
+ calculate_target_airspeed(1.3f * _parameters.airspeed_min),
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ true,
+ math::max(math::radians(pos_sp_triplet.current.pitch_min),
+ math::radians(10.0f)),
+ _global_pos.alt,
+ ground_speed,
+ TECS_MODE_TAKEOFF);
/* limit roll motion to ensure enough lift */
_att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f), math::radians(15.0f));
} else {
-
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _pos_sp_triplet.current.alt, calculate_target_airspeed(_parameters.airspeed_trim),
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, math::radians(_parameters.pitch_limit_min),
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max));
+ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
+ calculate_target_airspeed(_parameters.airspeed_trim),
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed);
}
} else {
@@ -1101,19 +1141,21 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
} else if (0/* posctrl mode enabled */) {
+ _was_pos_control_mode = false;
+
/** POSCTRL FLIGHT **/
- if (0/* switched from another mode to posctrl */) {
- _altctrl_hold_heading = _att.yaw;
- }
+ if (0/* switched from another mode to posctrl */) {
+ _altctrl_hold_heading = _att.yaw;
+ }
- if (0/* posctrl on and manual control yaw non-zero */) {
- _altctrl_hold_heading = _att.yaw + _manual.r;
- }
+ if (0/* posctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.r;
+ }
- //XXX not used
+ //XXX not used
- /* climb out control */
+ /* climb out control */
// bool climb_out = false;
//
// /* user wants to climb out */
@@ -1121,25 +1163,26 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// climb_out = true;
// }
- /* if in altctrl mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
- // XXX check if ground speed undershoot should be applied here
- float altctrl_airspeed = _parameters.airspeed_min +
- (_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.z;
+ // XXX check if ground speed undershoot should be applied here
+ float altctrl_airspeed = _parameters.airspeed_min +
+ (_parameters.airspeed_max - _parameters.airspeed_min) *
+ _manual.z;
- _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed_2d);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
- altctrl_airspeed,
- _airspeed.indicated_airspeed_m_s, eas2tas,
- false, _parameters.pitch_limit_min,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- _parameters.pitch_limit_min, _parameters.pitch_limit_max);
+
+ tecs_update_pitch_throttle(_global_pos.alt + _manual.x * 2.0f, altctrl_airspeed, eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed);
} else if (0/* altctrl mode enabled */) {
+ _was_pos_control_mode = false;
+
/** ALTCTRL FLIGHT **/
if (0/* switched from another mode to altctrl */) {
@@ -1160,8 +1203,6 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* user switched off throttle */
if (_manual.z < 0.1f) {
throttle_max = 0.0f;
- /* switch to pure pitch based altitude control, give up speed */
- _tecs.set_speed_weight(0.0f);
}
/* climb out control */
@@ -1172,18 +1213,19 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
climb_out = true;
}
- _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed_2d);
_att_sp.roll_body = _manual.y;
_att_sp.yaw_body = _manual.r;
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
- altctrl_airspeed,
- _airspeed.indicated_airspeed_m_s, eas2tas,
- climb_out, _parameters.pitch_limit_min,
- _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
- _parameters.pitch_limit_min, _parameters.pitch_limit_max);
+ tecs_update_pitch_throttle(_global_pos.alt + _manual.x * 2.0f, altctrl_airspeed, eas2tas,
+ math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
+ climb_out, math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt, ground_speed);
} else {
+ _was_pos_control_mode = false;
+
/** MANUAL FLIGHT **/
/* no flight mode applies, do not publish an attitude setpoint */
@@ -1200,9 +1242,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
}
else {
- _att_sp.thrust = math::min(_tecs.get_throttle_demand(), throttle_max);
+ _att_sp.thrust = math::min(_mTecs.getThrottleSetpoint(), throttle_max);
}
- _att_sp.pitch_body = _tecs.get_pitch_demand();
+ _att_sp.pitch_body = _mTecs.getPitchSetpoint();
if (_control_mode.flag_control_position_enabled) {
last_manual = false;
@@ -1256,6 +1298,8 @@ FixedwingPositionControl::task_main()
fds[1].fd = _global_pos_sub;
fds[1].events = POLLIN;
+ _task_running = true;
+
while (!_task_should_exit) {
/* wait for up to 500ms for data */
@@ -1316,7 +1360,7 @@ FixedwingPositionControl::task_main()
range_finder_poll();
// vehicle_baro_poll();
- math::Vector<2> ground_speed(_global_pos.vel_n, _global_pos.vel_e);
+ math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
math::Vector<2> current_position((float)_global_pos.lat, (float)_global_pos.lon);
/*
@@ -1356,6 +1400,8 @@ FixedwingPositionControl::task_main()
perf_end(_loop_perf);
}
+ _task_running = false;
+
warnx("exiting.\n");
_control_task = -1;
@@ -1378,6 +1424,30 @@ void FixedwingPositionControl::reset_landing_state()
land_onslope = false;
}
+void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_sp, float eas2tas,
+ float pitch_min_rad, float pitch_max_rad,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ bool climbout_mode, float climbout_pitch_min_rad,
+ float altitude,
+ const math::Vector<3> &ground_speed,
+ tecs_mode mode)
+{
+ /* Using mtecs library: prepare arguments for mtecs call */
+ float flightPathAngle = 0.0f;
+ float ground_speed_length = ground_speed.length();
+ if (ground_speed_length > FLT_EPSILON) {
+ flightPathAngle = -asinf(ground_speed(2)/ground_speed_length);
+ }
+ fwPosctrl::LimitOverride limitOverride;
+ if (climbout_mode) {
+ limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad);
+ } else {
+ limitOverride.disablePitchMinOverride();
+ }
+ _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
+ limitOverride);
+}
+
int
FixedwingPositionControl::start()
{
@@ -1387,7 +1457,7 @@ FixedwingPositionControl::start()
_control_task = task_spawn_cmd("fw_pos_control_l1",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4048,
+ 2000,
(main_t)&FixedwingPositionControl::task_main_trampoline,
nullptr);
@@ -1420,6 +1490,14 @@ int fw_pos_control_l1_main(int argc, char *argv[])
err(1, "start failed");
}
+ /* avoid memory fragmentation by not exiting start handler until the task has fully started */
+ while (l1_control::g_control == nullptr || !l1_control::g_control->task_running()) {
+ usleep(50000);
+ printf(".");
+ fflush(stdout);
+ }
+ printf("\n");
+
exit(0);
}
diff --git a/src/modules/fw_pos_control_l1/landingslope.cpp b/src/modules/fw_pos_control_l1/landingslope.cpp
index 8ce465fe8..42e00da05 100644
--- a/src/modules/fw_pos_control_l1/landingslope.cpp
+++ b/src/modules/fw_pos_control_l1/landingslope.cpp
@@ -46,16 +46,16 @@
#include <unistd.h>
#include <mathlib/mathlib.h>
-void Landingslope::update(float landing_slope_angle_rad,
- float flare_relative_alt,
- float motor_lim_relative_alt,
- float H1_virt)
+void Landingslope::update(float landing_slope_angle_rad_new,
+ float flare_relative_alt_new,
+ float motor_lim_relative_alt_new,
+ float H1_virt_new)
{
- _landing_slope_angle_rad = landing_slope_angle_rad;
- _flare_relative_alt = flare_relative_alt;
- _motor_lim_relative_alt = motor_lim_relative_alt;
- _H1_virt = H1_virt;
+ _landing_slope_angle_rad = landing_slope_angle_rad_new;
+ _flare_relative_alt = flare_relative_alt_new;
+ _motor_lim_relative_alt = motor_lim_relative_alt_new;
+ _H1_virt = H1_virt_new;
calculateSlopeValues();
}
diff --git a/src/modules/fw_pos_control_l1/landingslope.h b/src/modules/fw_pos_control_l1/landingslope.h
index b54fd501c..a5975ad43 100644
--- a/src/modules/fw_pos_control_l1/landingslope.h
+++ b/src/modules/fw_pos_control_l1/landingslope.h
@@ -123,10 +123,10 @@ public:
float getFlareCurveAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude);
- void update(float landing_slope_angle_rad,
- float flare_relative_alt,
- float motor_lim_relative_alt,
- float H1_virt);
+ void update(float landing_slope_angle_rad_new,
+ float flare_relative_alt_new,
+ float motor_lim_relative_alt_new,
+ float H1_virt_new);
inline float landing_slope_angle_rad() {return _landing_slope_angle_rad;}
diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk
index cf419ec7e..15b575b50 100644
--- a/src/modules/fw_pos_control_l1/module.mk
+++ b/src/modules/fw_pos_control_l1/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -39,4 +39,9 @@ MODULE_COMMAND = fw_pos_control_l1
SRCS = fw_pos_control_l1_main.cpp \
fw_pos_control_l1_params.c \
- landingslope.cpp
+ landingslope.cpp \
+ mtecs/mTecs.cpp \
+ mtecs/limitoverride.cpp \
+ mtecs/mTecs_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/fw_pos_control_l1/mtecs/limitoverride.cpp b/src/modules/fw_pos_control_l1/mtecs/limitoverride.cpp
new file mode 100644
index 000000000..58795edb6
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/limitoverride.cpp
@@ -0,0 +1,71 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 limitoverride.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include "limitoverride.h"
+
+namespace fwPosctrl {
+
+bool LimitOverride::applyOverride(BlockOutputLimiter &outputLimiterThrottle,
+ BlockOutputLimiter &outputLimiterPitch)
+{
+ bool ret = false;
+
+ if (overrideThrottleMinEnabled) {
+ outputLimiterThrottle.setMin(overrideThrottleMin);
+ ret = true;
+ }
+ if (overrideThrottleMaxEnabled) {
+ outputLimiterThrottle.setMax(overrideThrottleMax);
+ ret = true;
+ }
+ if (overridePitchMinEnabled) {
+ outputLimiterPitch.setMin(overridePitchMin);
+ ret = true;
+ }
+ if (overridePitchMaxEnabled) {
+ outputLimiterPitch.setMax(overridePitchMax);
+ ret = true;
+ }
+
+ return ret;
+}
+
+} /* namespace fwPosctrl */
diff --git a/src/modules/fw_pos_control_l1/mtecs/limitoverride.h b/src/modules/fw_pos_control_l1/mtecs/limitoverride.h
new file mode 100644
index 000000000..64c2e7bbd
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/limitoverride.h
@@ -0,0 +1,107 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 limitoverride.h
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+
+#ifndef LIMITOVERRIDE_H_
+#define LIMITOVERRIDE_H_
+
+#include "mTecs_blocks.h"
+
+namespace fwPosctrl
+{
+
+/* A small class which provides helper functions to override control output limits which are usually set by
+* parameters in special cases
+*/
+class LimitOverride
+{
+public:
+ LimitOverride() :
+ overrideThrottleMinEnabled(false),
+ overrideThrottleMaxEnabled(false),
+ overridePitchMinEnabled(false),
+ overridePitchMaxEnabled(false)
+ {};
+
+ ~LimitOverride() {};
+
+ /*
+ * Override the limits of the outputlimiter instances given by the arguments with the limits saved in
+ * this class (if enabled)
+ * @return true if the limit was applied
+ */
+ bool applyOverride(BlockOutputLimiter &outputLimiterThrottle,
+ BlockOutputLimiter &outputLimiterPitch);
+
+ /* Functions to enable or disable the override */
+ void enableThrottleMinOverride(float value) { enable(&overrideThrottleMinEnabled,
+ &overrideThrottleMin, value); }
+ void disableThrottleMinOverride() { disable(&overrideThrottleMinEnabled); }
+ void enableThrottleMaxOverride(float value) { enable(&overrideThrottleMaxEnabled,
+ &overrideThrottleMax, value); }
+ void disableThrottleMaxOverride() { disable(&overrideThrottleMaxEnabled); }
+ void enablePitchMinOverride(float value) { enable(&overridePitchMinEnabled,
+ &overridePitchMin, value); }
+ void disablePitchMinOverride() { disable(&overridePitchMinEnabled); }
+ void enablePitchMaxOverride(float value) { enable(&overridePitchMaxEnabled,
+ &overridePitchMax, value); }
+ void disablePitchMaxOverride() { disable(&overridePitchMaxEnabled); }
+
+protected:
+ bool overrideThrottleMinEnabled;
+ float overrideThrottleMin;
+ bool overrideThrottleMaxEnabled;
+ float overrideThrottleMax;
+ bool overridePitchMinEnabled;
+ float overridePitchMin; //in degrees (replaces param values)
+ bool overridePitchMaxEnabled;
+ float overridePitchMax; //in degrees (replaces param values)
+
+ /* Enable a specific limit override */
+ void enable(bool *flag, float *limit, float value) { *flag = true; *limit = value; };
+
+ /* Disable a specific limit override */
+ void disable(bool *flag) { *flag = false; };
+};
+
+} /* namespace fwPosctrl */
+
+#endif /* LIMITOVERRIDE_H_ */
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
new file mode 100644
index 000000000..2e37d166e
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
@@ -0,0 +1,313 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mTecs.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include "mTecs.h"
+
+#include <lib/geo/geo.h>
+#include <stdio.h>
+
+namespace fwPosctrl {
+
+mTecs::mTecs() :
+ SuperBlock(NULL, "MT"),
+ /* Parameters */
+ _mTecsEnabled(this, "ENABLED"),
+ _airspeedMin(this, "FW_AIRSPD_MIN", false),
+ /* Publications */
+ _status(&getPublications(), ORB_ID(tecs_status)),
+ /* control blocks */
+ _controlTotalEnergy(this, "THR"),
+ _controlEnergyDistribution(this, "PIT", true),
+ _controlAltitude(this, "FPA", true),
+ _controlAirSpeed(this, "ACC"),
+ _flightPathAngleLowpass(this, "FPA_LP"),
+ _airspeedLowpass(this, "A_LP"),
+ _airspeedDerivative(this, "AD"),
+ _throttleSp(0.0f),
+ _pitchSp(0.0f),
+ _BlockOutputLimiterTakeoffThrottle(this, "TKF_THR"),
+ _BlockOutputLimiterTakeoffPitch(this, "TKF_PIT", true),
+ _BlockOutputLimiterUnderspeedThrottle(this, "USP_THR"),
+ _BlockOutputLimiterUnderspeedPitch(this, "USP_PIT", true),
+ _BlockOutputLimiterLandThrottle(this, "LND_THR"),
+ _BlockOutputLimiterLandPitch(this, "LND_PIT", true),
+ timestampLastIteration(hrt_absolute_time()),
+ _firstIterationAfterReset(true),
+ _dtCalculated(false),
+ _counter(0),
+ _debug(false)
+{
+}
+
+mTecs::~mTecs()
+{
+}
+
+int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float altitudeSp, float airspeed,
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride)
+{
+ /* check if all input arguments are numbers and abort if not so */
+ if (!isfinite(flightPathAngle) || !isfinite(altitude) ||
+ !isfinite(altitudeSp) || !isfinite(airspeed) || !isfinite(airspeedSp) || !isfinite(mode)) {
+ return -1;
+ }
+
+ /* time measurement */
+ updateTimeMeasurement();
+
+ /* calculate flight path angle setpoint from altitude setpoint */
+ float flightPathAngleSp = _controlAltitude.update(altitudeSp - altitude);
+
+ /* Debug output */
+ if (_counter % 10 == 0) {
+ debug("***");
+ debug("updateAltitudeSpeed: altitudeSp %.4f, altitude %.4f, flightPathAngleSp %.4f", (double)altitudeSp, (double)altitude, (double)flightPathAngleSp);
+ }
+
+ /* Write part of the status message */
+ _status.altitudeSp = altitudeSp;
+ _status.altitude = altitude;
+
+
+ /* use flightpath angle setpoint for total energy control */
+ return updateFlightPathAngleSpeed(flightPathAngle, flightPathAngleSp, airspeed,
+ airspeedSp, mode, limitOverride);
+}
+
+int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAngleSp, float airspeed,
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride)
+{
+ /* check if all input arguments are numbers and abort if not so */
+ if (!isfinite(flightPathAngle) || !isfinite(flightPathAngleSp) ||
+ !isfinite(airspeed) || !isfinite(airspeedSp) || !isfinite(mode)) {
+ return -1;
+ }
+
+ /* time measurement */
+ updateTimeMeasurement();
+
+ /* Filter airspeed */
+ float airspeedFiltered = _airspeedLowpass.update(airspeed);
+
+ /* calculate longitudinal acceleration setpoint from airspeed setpoint*/
+ float accelerationLongitudinalSp = _controlAirSpeed.update(airspeedSp - airspeedFiltered);
+
+ /* Debug output */
+ if (_counter % 10 == 0) {
+ debug("updateFlightPathAngleSpeed airspeedSp %.4f, airspeed %.4f airspeedFiltered %.4f,"
+ "accelerationLongitudinalSp%.4f",
+ (double)airspeedSp, (double)airspeed,
+ (double)airspeedFiltered, (double)accelerationLongitudinalSp);
+ }
+
+ /* Write part of the status message */
+ _status.airspeedSp = airspeedSp;
+ _status.airspeed = airspeed;
+ _status.airspeedFiltered = airspeedFiltered;
+
+
+ /* use longitudinal acceleration setpoint for total energy control */
+ return updateFlightPathAngleAcceleration(flightPathAngle, flightPathAngleSp, airspeedFiltered,
+ accelerationLongitudinalSp, mode, limitOverride);
+}
+
+int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flightPathAngleSp, float airspeedFiltered,
+ float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride)
+{
+ /* check if all input arguments are numbers and abort if not so */
+ if (!isfinite(flightPathAngle) || !isfinite(flightPathAngleSp) ||
+ !isfinite(airspeedFiltered) || !isfinite(accelerationLongitudinalSp) || !isfinite(mode)) {
+ return -1;
+ }
+ /* time measurement */
+ updateTimeMeasurement();
+
+ /* update parameters first */
+ updateParams();
+
+ /* Filter flightpathangle */
+ float flightPathAngleFiltered = _flightPathAngleLowpass.update(flightPathAngle);
+
+ /* calculate values (energies) */
+ float flightPathAngleError = flightPathAngleSp - flightPathAngleFiltered;
+ float airspeedDerivative = 0.0f;
+ if(_airspeedDerivative.getDt() > 0.0f) {
+ airspeedDerivative = _airspeedDerivative.update(airspeedFiltered);
+ }
+ float airspeedDerivativeNorm = airspeedDerivative / CONSTANTS_ONE_G;
+ float airspeedDerivativeSp = accelerationLongitudinalSp;
+ float airspeedDerivativeNormSp = airspeedDerivativeSp / CONSTANTS_ONE_G;
+ float airspeedDerivativeNormError = airspeedDerivativeNormSp - airspeedDerivativeNorm;
+
+ float totalEnergyRate = flightPathAngleFiltered + airspeedDerivativeNorm;
+ float totalEnergyRateError = flightPathAngleError + airspeedDerivativeNormError;
+ float totalEnergyRateSp = flightPathAngleSp + airspeedDerivativeNormSp;
+ float totalEnergyRateError2 = totalEnergyRateSp - totalEnergyRate;
+
+ float energyDistributionRate = flightPathAngleFiltered - airspeedDerivativeNorm;
+ float energyDistributionRateError = flightPathAngleError - airspeedDerivativeNormError;
+ float energyDistributionRateSp = flightPathAngleSp - airspeedDerivativeNormSp;
+ float energyDistributionRateError2 = energyDistributionRateSp - energyDistributionRate;
+
+ /* Debug output */
+ if (_counter % 10 == 0) {
+ debug("totalEnergyRateSp %.2f, totalEnergyRate %.2f, totalEnergyRateError %.2f totalEnergyRateError2 %.2f airspeedDerivativeNorm %.4f",
+ (double)totalEnergyRateSp, (double)totalEnergyRate, (double)totalEnergyRateError, (double)totalEnergyRateError2, (double)airspeedDerivativeNorm);
+ debug("energyDistributionRateSp %.2f, energyDistributionRate %.2f, energyDistributionRateError %.2f energyDistributionRateError2 %.2f",
+ (double)energyDistributionRateSp, (double)energyDistributionRate, (double)energyDistributionRateError, (double)energyDistributionRateError2);
+ }
+
+ /* Check airspeed: if below safe value switch to underspeed mode (if not in land or takeoff mode) */
+ if (mode != TECS_MODE_LAND && mode != TECS_MODE_TAKEOFF && airspeedFiltered < _airspeedMin.get()) {
+ mode = TECS_MODE_UNDERSPEED;
+ }
+
+ /* Set special ouput limiters if we are not in TECS_MODE_NORMAL */
+ BlockOutputLimiter *outputLimiterThrottle = &_controlTotalEnergy.getOutputLimiter();
+ BlockOutputLimiter *outputLimiterPitch = &_controlEnergyDistribution.getOutputLimiter();
+ if (mode == TECS_MODE_TAKEOFF) {
+ outputLimiterThrottle = &_BlockOutputLimiterTakeoffThrottle;
+ outputLimiterPitch = &_BlockOutputLimiterTakeoffPitch;
+ } else if (mode == TECS_MODE_LAND) {
+ // only limit pitch but do not limit throttle
+ outputLimiterPitch = &_BlockOutputLimiterLandPitch;
+ } else if (mode == TECS_MODE_LAND_THROTTLELIM) {
+ outputLimiterThrottle = &_BlockOutputLimiterLandThrottle;
+ outputLimiterPitch = &_BlockOutputLimiterLandPitch;
+ } else if (mode == TECS_MODE_UNDERSPEED) {
+ outputLimiterThrottle = &_BlockOutputLimiterUnderspeedThrottle;
+ outputLimiterPitch = &_BlockOutputLimiterUnderspeedPitch;
+ }
+
+ /* Apply overrride given by the limitOverride argument (this is used for limits which are not given by
+ * parameters such as pitch limits with takeoff waypoints or throttle limits when the launchdetector
+ * is running) */
+ limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch);
+
+ /* Write part of the status message */
+ _status.flightPathAngleSp = flightPathAngleSp;
+ _status.flightPathAngle = flightPathAngle;
+ _status.flightPathAngleFiltered = flightPathAngleFiltered;
+ _status.airspeedDerivativeSp = airspeedDerivativeSp;
+ _status.airspeedDerivative = airspeedDerivative;
+ _status.totalEnergyRateSp = totalEnergyRateSp;
+ _status.totalEnergyRate = totalEnergyRate;
+ _status.energyDistributionRateSp = energyDistributionRateSp;
+ _status.energyDistributionRate = energyDistributionRate;
+ _status.mode = mode;
+
+ /** update control blocks **/
+ /* update total energy rate control block */
+ _throttleSp = _controlTotalEnergy.update(totalEnergyRateSp, totalEnergyRateError, outputLimiterThrottle);
+
+ /* update energy distribution rate control block */
+ _pitchSp = _controlEnergyDistribution.update(energyDistributionRateSp, energyDistributionRateError, outputLimiterPitch);
+
+
+ if (_counter % 10 == 0) {
+ debug("_throttleSp %.1f, _pitchSp %.1f, flightPathAngleSp %.1f, flightPathAngle %.1f accelerationLongitudinalSp %.1f, airspeedDerivative %.1f",
+ (double)_throttleSp, (double)_pitchSp,
+ (double)flightPathAngleSp, (double)flightPathAngle,
+ (double)accelerationLongitudinalSp, (double)airspeedDerivative);
+ }
+
+ /* publish status messge */
+ _status.update();
+
+ /* clean up */
+ _firstIterationAfterReset = false;
+ _dtCalculated = false;
+
+ _counter++;
+
+ return 0;
+}
+
+void mTecs::resetIntegrators()
+{
+ _controlTotalEnergy.getIntegral().setY(0.0f);
+ _controlEnergyDistribution.getIntegral().setY(0.0f);
+ timestampLastIteration = hrt_absolute_time();
+ _firstIterationAfterReset = true;
+}
+
+void mTecs::resetDerivatives(float airspeed)
+{
+ _airspeedDerivative.setU(airspeed);
+}
+
+
+void mTecs::updateTimeMeasurement()
+{
+ if (!_dtCalculated) {
+ float deltaTSeconds = 0.0f;
+ if (!_firstIterationAfterReset) {
+ hrt_abstime timestampNow = hrt_absolute_time();
+ deltaTSeconds = (float)(timestampNow - timestampLastIteration) * 1e-6f;
+ timestampLastIteration = timestampNow;
+ }
+ setDt(deltaTSeconds);
+
+ _dtCalculated = true;
+ }
+}
+
+void mTecs::debug_print(const char *fmt, va_list args)
+{
+ fprintf(stderr, "%s: ", "[mtecs]");
+ vfprintf(stderr, fmt, args);
+
+ fprintf(stderr, "\n");
+}
+
+void mTecs::debug(const char *fmt, ...) {
+
+ if (!_debug) {
+ return;
+ }
+
+ va_list args;
+
+ va_start(args, fmt);
+ debug_print(fmt, args);
+}
+
+} /* namespace fwPosctrl */
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.h b/src/modules/fw_pos_control_l1/mtecs/mTecs.h
new file mode 100644
index 000000000..efa89a5d3
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.h
@@ -0,0 +1,155 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mTecs.h
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+
+#ifndef MTECS_H_
+#define MTECS_H_
+
+#include "mTecs_blocks.h"
+#include "limitoverride.h"
+
+#include <controllib/block/BlockParam.hpp>
+#include <drivers/drv_hrt.h>
+#include <uORB/Publication.hpp>
+#include <uORB/topics/tecs_status.h>
+
+namespace fwPosctrl
+{
+
+/* Main class of the mTecs */
+class mTecs : public control::SuperBlock
+{
+public:
+ mTecs();
+ virtual ~mTecs();
+
+ /*
+ * Control in altitude setpoint and speed mode
+ */
+ int updateAltitudeSpeed(float flightPathAngle, float altitude, float altitudeSp, float airspeed,
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
+
+ /*
+ * Control in flightPathAngle setpoint (flollow a slope etc.) and speed mode
+ */
+ int updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAngleSp, float airspeed,
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
+
+ /*
+ * Control in flightPathAngle setpoint (flollow a slope etc.) and acceleration mode (base case)
+ */
+ int updateFlightPathAngleAcceleration(float flightPathAngle, float flightPathAngleSp, float airspeedFiltered,
+ float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride);
+
+ /*
+ * Reset all integrators
+ */
+ void resetIntegrators();
+
+ /*
+ * Reset all derivative calculations
+ */
+ void resetDerivatives(float airspeed);
+
+ /* Accessors */
+ bool getEnabled() { return _mTecsEnabled.get() > 0; }
+ float getThrottleSetpoint() { return _throttleSp; }
+ float getPitchSetpoint() { return _pitchSp; }
+ float airspeedLowpassUpdate(float input) { return _airspeedLowpass.update(input); }
+
+protected:
+ /* parameters */
+ control::BlockParamInt _mTecsEnabled; /**< 1 if mTecs is enabled */
+ control::BlockParamFloat _airspeedMin; /**< minimal airspeed */
+
+ /* Publications */
+ uORB::Publication<tecs_status_s> _status; /**< publish internal values for logging */
+
+ /* control blocks */
+ BlockFFPILimitedCustom _controlTotalEnergy; /**< FFPI controller for total energy control: output
+ is throttle */
+ BlockFFPILimitedCustom _controlEnergyDistribution; /**< FFPI controller for energy distribution control:
+ output is pitch */
+ BlockPDLimited _controlAltitude; /**< PD controller for altitude: output is the flight
+ path angle setpoint */
+ BlockPDLimited _controlAirSpeed; /**< PD controller for airspeed: output is acceleration
+ setpoint */
+
+ /* Other calculation Blocks */
+ control::BlockLowPass _flightPathAngleLowpass; /**< low pass filter for the flight path angle */
+ control::BlockLowPass _airspeedLowpass; /**< low pass filter for airspeed */
+ control::BlockDerivative _airspeedDerivative; /**< airspeed derivative calulation */
+
+ /* Output setpoints */
+ float _throttleSp; /**< Throttle Setpoint from 0 to 1 */
+ float _pitchSp; /**< Pitch Setpoint from -pi to pi */
+
+ /* Output Limits in special modes */
+ BlockOutputLimiter _BlockOutputLimiterTakeoffThrottle; /**< Throttle Limits during takeoff */
+ BlockOutputLimiter _BlockOutputLimiterTakeoffPitch; /**< Pitch Limit during takeoff */
+ BlockOutputLimiter _BlockOutputLimiterUnderspeedThrottle; /**< Throttle Limits when underspeed is detected */
+ BlockOutputLimiter _BlockOutputLimiterUnderspeedPitch; /**< Pitch Limit when underspeed is detected */
+ BlockOutputLimiter _BlockOutputLimiterLandThrottle; /**< Throttle Limits during landing (only in
+ last phase)*/
+ BlockOutputLimiter _BlockOutputLimiterLandPitch; /**< Pitch Limit during landing */
+
+ /* Time measurements */
+ hrt_abstime timestampLastIteration; /**< Saves the result of hrt_absolute_time() of the last iteration */
+
+ bool _firstIterationAfterReset; /**< True during the first iteration after a reset */
+ bool _dtCalculated; /**< True if dt has been calculated in this iteration */
+
+ int _counter;
+ bool _debug; ///< Set true to enable debug output
+
+
+ static void debug_print(const char *fmt, va_list args);
+ void debug(const char *fmt, ...);
+
+ /*
+ * Measure and update the time step dt if this was not already done in the current iteration
+ */
+ void updateTimeMeasurement();
+};
+
+} /* namespace fwPosctrl */
+
+#endif /* MTECS_H_ */
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h
new file mode 100644
index 000000000..c22e60ae0
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h
@@ -0,0 +1,220 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mTecs_blocks.h
+ *
+ * Custom blocks for the mTecs
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#pragma once
+
+#include <controllib/blocks.hpp>
+#include <systemlib/err.h>
+
+namespace fwPosctrl
+{
+
+using namespace control;
+
+/* An block which can be used to limit the output */
+class BlockOutputLimiter: public SuperBlock
+{
+public:
+// methods
+ BlockOutputLimiter(SuperBlock *parent, const char *name, bool fAngularLimit = false) :
+ SuperBlock(parent, name),
+ _isAngularLimit(fAngularLimit),
+ _min(this, "MIN"),
+ _max(this, "MAX")
+ {};
+ virtual ~BlockOutputLimiter() {};
+ /*
+ * Imposes the limits given by _min and _max on value
+ *
+ * @param value is changed to be on the interval _min to _max
+ * @param difference if the value is changed this corresponds to the change of value * (-1)
+ * otherwise unchanged
+ * @return: true if the limit is applied, false otherwise
+ */
+ bool limit(float& value, float& difference) {
+ float minimum = isAngularLimit() ? getMin() * M_DEG_TO_RAD_F : getMin();
+ float maximum = isAngularLimit() ? getMax() * M_DEG_TO_RAD_F : getMax();
+ if (value < minimum) {
+ difference = value - minimum;
+ value = minimum;
+ return true;
+ } else if (value > maximum) {
+ difference = value - maximum;
+ value = maximum;
+ return true;
+ }
+ return false;
+ }
+//accessor:
+ bool isAngularLimit() {return _isAngularLimit ;}
+ float getMin() { return _min.get(); }
+ float getMax() { return _max.get(); }
+ void setMin(float value) { _min.set(value); }
+ void setMax(float value) { _max.set(value); }
+protected:
+//attributes
+ bool _isAngularLimit;
+ control::BlockParamFloat _min;
+ control::BlockParamFloat _max;
+};
+
+
+/* A combination of feed forward, P and I gain using the output limiter*/
+class BlockFFPILimited: public SuperBlock
+{
+public:
+// methods
+ BlockFFPILimited(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
+ SuperBlock(parent, name),
+ _outputLimiter(this, "", isAngularLimit),
+ _integral(this, "I"),
+ _kFF(this, "FF"),
+ _kP(this, "P"),
+ _kI(this, "I"),
+ _offset(this, "OFF")
+ {};
+ virtual ~BlockFFPILimited() {};
+ float update(float inputValue, float inputError) { return calcLimitedOutput(inputValue, inputError, _outputLimiter); }
+// accessors
+ BlockIntegral &getIntegral() { return _integral; }
+ float getKFF() { return _kFF.get(); }
+ float getKP() { return _kP.get(); }
+ float getKI() { return _kI.get(); }
+ float getOffset() { return _offset.get(); }
+ BlockOutputLimiter &getOutputLimiter() { return _outputLimiter; };
+protected:
+ BlockOutputLimiter _outputLimiter;
+
+ float calcUnlimitedOutput(float inputValue, float inputError) {return getOffset() + getKFF() * inputValue + getKP() * inputError + getKI() * getIntegral().update(inputError);}
+ float calcLimitedOutput(float inputValue, float inputError, BlockOutputLimiter &outputLimiter) {
+ float difference = 0.0f;
+ float integralYPrevious = _integral.getY();
+ float output = calcUnlimitedOutput(inputValue, inputError);
+ if(outputLimiter.limit(output, difference) &&
+ (((difference < 0) && (getKI() * getIntegral().getY() < 0)) ||
+ ((difference > 0) && (getKI() * getIntegral().getY() > 0)))) {
+ getIntegral().setY(integralYPrevious);
+ }
+ return output;
+ }
+private:
+ BlockIntegral _integral;
+ BlockParamFloat _kFF;
+ BlockParamFloat _kP;
+ BlockParamFloat _kI;
+ BlockParamFloat _offset;
+};
+
+/* A combination of feed forward, P and I gain using the output limiter with the option to provide a special output limiter (for example for takeoff)*/
+class BlockFFPILimitedCustom: public BlockFFPILimited
+{
+public:
+// methods
+ BlockFFPILimitedCustom(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
+ BlockFFPILimited(parent, name, isAngularLimit)
+ {};
+ virtual ~BlockFFPILimitedCustom() {};
+ float update(float inputValue, float inputError, BlockOutputLimiter *outputLimiter = NULL) {
+ return calcLimitedOutput(inputValue, inputError, outputLimiter == NULL ? _outputLimiter : *outputLimiter);
+ }
+};
+
+/* A combination of P gain and output limiter */
+class BlockPLimited: public SuperBlock
+{
+public:
+// methods
+ BlockPLimited(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
+ SuperBlock(parent, name),
+ _kP(this, "P"),
+ _outputLimiter(this, "", isAngularLimit)
+ {};
+ virtual ~BlockPLimited() {};
+ float update(float input) {
+ float difference = 0.0f;
+ float output = getKP() * input;
+ getOutputLimiter().limit(output, difference);
+ return output;
+ }
+// accessors
+ BlockOutputLimiter &getOutputLimiter() { return _outputLimiter; };
+ float getKP() { return _kP.get(); }
+private:
+ control::BlockParamFloat _kP;
+ BlockOutputLimiter _outputLimiter;
+};
+
+/* A combination of P, D gains and output limiter */
+class BlockPDLimited: public SuperBlock
+{
+public:
+// methods
+ BlockPDLimited(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
+ SuperBlock(parent, name),
+ _kP(this, "P"),
+ _kD(this, "D"),
+ _derivative(this, "D"),
+ _outputLimiter(this, "", isAngularLimit)
+ {};
+ virtual ~BlockPDLimited() {};
+ float update(float input) {
+ float difference = 0.0f;
+ float output = getKP() * input + (getDerivative().getDt() > 0.0f ? getKD() * getDerivative().update(input) : 0.0f);
+ getOutputLimiter().limit(output, difference);
+
+ return output;
+ }
+// accessors
+ float getKP() { return _kP.get(); }
+ float getKD() { return _kD.get(); }
+ BlockDerivative &getDerivative() { return _derivative; }
+ BlockOutputLimiter &getOutputLimiter() { return _outputLimiter; };
+private:
+ control::BlockParamFloat _kP;
+ control::BlockParamFloat _kD;
+ BlockDerivative _derivative;
+ BlockOutputLimiter _outputLimiter;
+};
+
+}
+
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c
new file mode 100644
index 000000000..5b9238780
--- /dev/null
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c
@@ -0,0 +1,419 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mTecs_params.c
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+/*
+ * Controller parameters, accessible via MAVLink
+ */
+
+/**
+ * mTECS enabled
+ *
+ * Set to 1 to enable mTECS
+ *
+ * @min 0
+ * @max 1
+ * @group mTECS
+ */
+PARAM_DEFINE_INT32(MT_ENABLED, 1);
+
+/**
+ * Total Energy Rate Control Feedforward
+ * Maps the total energy rate setpoint to the throttle setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_FF, 0.7f);
+
+/**
+ * Total Energy Rate Control P
+ * Maps the total energy rate error to the throttle setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_P, 0.1f);
+
+/**
+ * Total Energy Rate Control I
+ * Maps the integrated total energy rate to the throttle setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_I, 0.25f);
+
+/**
+ * Total Energy Rate Control Offset (Cruise throttle sp)
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_OFF, 0.7f);
+
+/**
+ * Energy Distribution Rate Control Feedforward
+ * Maps the energy distribution rate setpoint to the pitch setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_FF, 0.4f);
+
+/**
+ * Energy Distribution Rate Control P
+ * Maps the energy distribution rate error to the pitch setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_P, 0.03f);
+
+/**
+ * Energy Distribution Rate Control I
+ * Maps the integrated energy distribution rate error to the pitch setpoint
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_I, 0.03f);
+
+
+/**
+ * Total Energy Distribution Offset (Cruise pitch sp)
+ *
+ * @min 0.0
+ * @max 10.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_OFF, 0.0f);
+
+/**
+ * Minimal Throttle Setpoint
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_MIN, 0.0f);
+
+/**
+ * Maximal Throttle Setpoint
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_MAX, 1.0f);
+
+/**
+ * Minimal Pitch Setpoint in Degrees
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_MIN, -45.0f);
+
+/**
+ * Maximal Pitch Setpoint in Degrees
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_MAX, 20.0f);
+
+/**
+ * Lowpass (cutoff freq.) for the flight path angle
+ *
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_LP, 1.0f);
+
+/**
+ * P gain for the altitude control
+ * Maps the altitude error to the flight path angle setpoint
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_P, 0.3f);
+
+/**
+ * D gain for the altitude control
+ * Maps the change of altitude error to the flight path angle setpoint
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_D, 0.0f);
+
+/**
+ * Lowpass for FPA error derivative calculation (see MT_FPA_D)
+ *
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_D_LP, 1.0f);
+
+
+/**
+ * Minimal flight path angle setpoint
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_MIN, -20.0f);
+
+/**
+ * Maximal flight path angle setpoint
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_FPA_MAX, 30.0f);
+
+/**
+ * Lowpass (cutoff freq.) for airspeed
+ *
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_A_LP, 1.0f);
+
+/**
+ * P gain for the airspeed control
+ * Maps the airspeed error to the acceleration setpoint
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_ACC_P, 0.3f);
+
+/**
+ * D gain for the airspeed control
+ * Maps the change of airspeed error to the acceleration setpoint
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_ACC_D, 0.0f);
+
+/**
+ * Lowpass for ACC error derivative calculation (see MT_ACC_D)
+ *
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_ACC_D_LP, 1.0f);
+
+/**
+ * Minimal acceleration (air)
+ *
+ * @unit m/s^2
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_ACC_MIN, -40.0f);
+
+/**
+ * Maximal acceleration (air)
+ *
+* @unit m/s^2
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_ACC_MAX, 40.0f);
+
+/**
+ * Airspeed derivative calculation lowpass
+ *
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_AD_LP, 1.0f);
+
+/**
+ * Minimal throttle during takeoff
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_TKF_THR_MIN, 1.0f);
+
+/**
+ * Maximal throttle during takeoff
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_TKF_THR_MAX, 1.0f);
+
+/**
+ * Minimal pitch during takeoff
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_TKF_PIT_MIN, 0.0f);
+
+/**
+ * Maximal pitch during takeoff
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_TKF_PIT_MAX, 45.0f);
+
+/**
+ * Minimal throttle in underspeed mode
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_USP_THR_MIN, 1.0f);
+
+/**
+ * Maximal throttle in underspeed mode
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_USP_THR_MAX, 1.0f);
+
+/**
+ * Minimal pitch in underspeed mode
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_USP_PIT_MIN, -45.0f);
+
+/**
+ * Maximal pitch in underspeed mode
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_USP_PIT_MAX, 0.0f);
+
+/**
+ * Minimal throttle in landing mode (only last phase of landing)
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_LND_THR_MIN, 0.0f);
+
+/**
+ * Maximal throttle in landing mode (only last phase of landing)
+ *
+ * @min 0.0f
+ * @max 1.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_LND_THR_MAX, 0.0f);
+
+/**
+ * Minimal pitch in landing mode
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_LND_PIT_MIN, -5.0f);
+
+/**
+ * Maximal pitch in landing mode
+ *
+ * @min -90.0f
+ * @max 90.0f
+ * @unit deg
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_LND_PIT_MAX, 15.0f);
+
+/**
+ * Integrator Limit for Total Energy Rate Control
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_THR_I_MAX, 10.0f);
+
+/**
+ * Integrator Limit for Energy Distribution Rate Control
+ *
+ * @min 0.0f
+ * @max 10.0f
+ * @group mTECS
+ */
+PARAM_DEFINE_FLOAT(MT_PIT_I_MAX, 10.0f);
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index 6dfd22fdf..7758faed7 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -181,16 +181,13 @@ int gpio_led_main(int argc, char *argv[])
} else {
gpio_led_started = true;
warnx("start, using pin: %s", pin_name);
+ exit(0);
}
-
- exit(0);
-
-
} else if (!strcmp(argv[1], "stop")) {
if (gpio_led_started) {
gpio_led_started = false;
warnx("stop");
-
+ exit(0);
} else {
errx(1, "not running");
}
@@ -264,7 +261,7 @@ void gpio_led_cycle(FAR void *arg)
pattern = 0x2A; // *_*_*_ fast blink (armed, error)
} else if (priv->status.arming_state == ARMING_STATE_ARMED) {
- if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE && priv->status.failsafe_state == FAILSAFE_STATE_NORMAL) {
+ if (priv->status.battery_warning == VEHICLE_BATTERY_WARNING_NONE && !priv->status.failsafe) {
pattern = 0x3f; // ****** solid (armed)
} else {
diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp
index 1c1e097a4..fccd4d9a5 100644
--- a/src/modules/mavlink/mavlink_commands.cpp
+++ b/src/modules/mavlink/mavlink_commands.cpp
@@ -40,34 +40,31 @@
#include "mavlink_commands.h"
-MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel)
+MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0)
{
_cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command));
- _cmd = (struct vehicle_command_s *)_cmd_sub->get_data();
-}
-
-MavlinkCommandsStream::~MavlinkCommandsStream()
-{
}
void
MavlinkCommandsStream::update(const hrt_abstime t)
{
- if (_cmd_sub->update(t)) {
+ struct vehicle_command_s cmd;
+
+ if (_cmd_sub->update(&_cmd_time, &cmd)) {
/* only send commands for other systems/components */
- if (_cmd->target_system != mavlink_system.sysid || _cmd->target_component != mavlink_system.compid) {
+ if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) {
mavlink_msg_command_long_send(_channel,
- _cmd->target_system,
- _cmd->target_component,
- _cmd->command,
- _cmd->confirmation,
- _cmd->param1,
- _cmd->param2,
- _cmd->param3,
- _cmd->param4,
- _cmd->param5,
- _cmd->param6,
- _cmd->param7);
+ cmd.target_system,
+ cmd.target_component,
+ cmd.command,
+ cmd.confirmation,
+ cmd.param1,
+ cmd.param2,
+ cmd.param3,
+ cmd.param4,
+ cmd.param5,
+ cmd.param6,
+ cmd.param7);
}
}
}
diff --git a/src/modules/mavlink/mavlink_commands.h b/src/modules/mavlink/mavlink_commands.h
index 6255d65df..abdba34b9 100644
--- a/src/modules/mavlink/mavlink_commands.h
+++ b/src/modules/mavlink/mavlink_commands.h
@@ -55,10 +55,10 @@ private:
MavlinkOrbSubscription *_cmd_sub;
struct vehicle_command_s *_cmd;
mavlink_channel_t _channel;
+ uint64_t _cmd_time;
public:
MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel);
- ~MavlinkCommandsStream();
void update(const hrt_abstime t);
};
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
new file mode 100644
index 000000000..675a6870e
--- /dev/null
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -0,0 +1,423 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <crc32.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <fcntl.h>
+
+#include "mavlink_ftp.h"
+
+MavlinkFTP *MavlinkFTP::_server;
+
+MavlinkFTP *
+MavlinkFTP::getServer()
+{
+ // XXX this really cries out for some locking...
+ if (_server == nullptr) {
+ _server = new MavlinkFTP;
+ }
+ return _server;
+}
+
+MavlinkFTP::MavlinkFTP()
+{
+ // initialise the request freelist
+ dq_init(&_workFree);
+ sem_init(&_lock, 0, 1);
+
+ // initialize session list
+ for (size_t i=0; i<kMaxSession; i++) {
+ _session_fds[i] = -1;
+ }
+
+ // drop work entries onto the free list
+ for (unsigned i = 0; i < kRequestQueueSize; i++) {
+ _qFree(&_workBufs[i]);
+ }
+
+}
+
+void
+MavlinkFTP::handle_message(Mavlink* mavlink, mavlink_message_t *msg)
+{
+ // get a free request
+ auto req = _dqFree();
+
+ // if we couldn't get a request slot, just drop it
+ if (req != nullptr) {
+
+ // decode the request
+ if (req->decode(mavlink, msg)) {
+
+ // and queue it for the worker
+ work_queue(LPWORK, &req->work, &MavlinkFTP::_workerTrampoline, req, 0);
+ } else {
+ _qFree(req);
+ }
+ }
+}
+
+void
+MavlinkFTP::_workerTrampoline(void *arg)
+{
+ auto req = reinterpret_cast<Request *>(arg);
+ auto server = MavlinkFTP::getServer();
+
+ // call the server worker with the work item
+ server->_worker(req);
+}
+
+void
+MavlinkFTP::_worker(Request *req)
+{
+ auto hdr = req->header();
+ ErrorCode errorCode = kErrNone;
+ uint32_t messageCRC;
+
+ // basic sanity checks; must validate length before use
+ if ((hdr->magic != kProtocolMagic) || (hdr->size > kMaxDataLength)) {
+ errorCode = kErrNoRequest;
+ goto out;
+ }
+
+ // check request CRC to make sure this is one of ours
+ messageCRC = hdr->crc32;
+ hdr->crc32 = 0;
+ if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
+ errorCode = kErrNoRequest;
+ goto out;
+ warnx("ftp: bad crc");
+ }
+
+ //printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+
+ switch (hdr->opcode) {
+ case kCmdNone:
+ break;
+
+ case kCmdTerminate:
+ errorCode = _workTerminate(req);
+ break;
+
+ case kCmdReset:
+ errorCode = _workReset();
+ break;
+
+ case kCmdList:
+ errorCode = _workList(req);
+ break;
+
+ case kCmdOpen:
+ errorCode = _workOpen(req, false);
+ break;
+
+ case kCmdCreate:
+ errorCode = _workOpen(req, true);
+ break;
+
+ case kCmdRead:
+ errorCode = _workRead(req);
+ break;
+
+ case kCmdWrite:
+ errorCode = _workWrite(req);
+ break;
+
+ case kCmdRemove:
+ errorCode = _workRemove(req);
+ break;
+
+ default:
+ errorCode = kErrNoRequest;
+ break;
+ }
+
+out:
+ // handle success vs. error
+ if (errorCode == kErrNone) {
+ hdr->opcode = kRspAck;
+ //warnx("FTP: ack\n");
+ } else {
+ warnx("FTP: nak %u", errorCode);
+ hdr->opcode = kRspNak;
+ hdr->size = 1;
+ hdr->data[0] = errorCode;
+ }
+
+ // respond to the request
+ _reply(req);
+
+ // free the request buffer back to the freelist
+ _qFree(req);
+}
+
+void
+MavlinkFTP::_reply(Request *req)
+{
+ auto hdr = req->header();
+
+ // message is assumed to be already constructed in the request buffer, so generate the CRC
+ hdr->crc32 = 0;
+ hdr->crc32 = crc32(req->rawData(), req->dataSize());
+
+ // then pack and send the reply back to the request source
+ req->reply();
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workList(Request *req)
+{
+ auto hdr = req->header();
+
+ char dirPath[kMaxDataLength];
+ strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+
+ DIR *dp = opendir(dirPath);
+
+ if (dp == nullptr) {
+ warnx("FTP: can't open path '%s'", dirPath);
+ return kErrNotDir;
+ }
+
+ //warnx("FTP: list %s offset %d", dirPath, hdr->offset);
+
+ ErrorCode errorCode = kErrNone;
+ struct dirent entry, *result = nullptr;
+ unsigned offset = 0;
+
+ // move to the requested offset
+ seekdir(dp, hdr->offset);
+
+ for (;;) {
+ // read the directory entry
+ if (readdir_r(dp, &entry, &result)) {
+ warnx("FTP: list %s readdir_r failure\n", dirPath);
+ errorCode = kErrIO;
+ break;
+ }
+
+ // no more entries?
+ if (result == nullptr) {
+ if (hdr->offset != 0 && offset == 0) {
+ // User is requesting subsequent dir entries but there were none. This means the user asked
+ // to seek past EOF.
+ errorCode = kErrEOF;
+ }
+ // Otherwise we are just at the last directory entry, so we leave the errorCode at kErrorNone to signal that
+ break;
+ }
+
+ // name too big to fit?
+ if ((strlen(entry.d_name) + offset + 2) > kMaxDataLength) {
+ break;
+ }
+
+ // store the type marker
+ switch (entry.d_type) {
+ case DTYPE_FILE:
+ hdr->data[offset++] = kDirentFile;
+ break;
+ case DTYPE_DIRECTORY:
+ hdr->data[offset++] = kDirentDir;
+ break;
+ default:
+ hdr->data[offset++] = kDirentUnknown;
+ break;
+ }
+
+ // copy the name, which we know will fit
+ strcpy((char *)&hdr->data[offset], entry.d_name);
+ //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
+ offset += strlen(entry.d_name) + 1;
+ }
+
+ closedir(dp);
+ hdr->size = offset;
+
+ return errorCode;
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workOpen(Request *req, bool create)
+{
+ auto hdr = req->header();
+
+ int session_index = _findUnusedSession();
+ if (session_index < 0) {
+ return kErrNoSession;
+ }
+
+ int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
+
+ int fd = ::open(req->dataAsCString(), oflag);
+ if (fd < 0) {
+ return create ? kErrPerm : kErrNotFile;
+ }
+ _session_fds[session_index] = fd;
+
+ hdr->session = session_index;
+ hdr->size = 0;
+
+ return kErrNone;
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRead(Request *req)
+{
+ auto hdr = req->header();
+
+ int session_index = hdr->session;
+
+ if (!_validSession(session_index)) {
+ return kErrNoSession;
+ }
+
+ // Seek to the specified position
+ //warnx("seek %d", hdr->offset);
+ if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
+ // Unable to see to the specified location
+ warnx("seek fail");
+ return kErrEOF;
+ }
+
+ int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
+ if (bytes_read < 0) {
+ // Negative return indicates error other than eof
+ warnx("read fail %d", bytes_read);
+ return kErrIO;
+ }
+
+ hdr->size = bytes_read;
+
+ return kErrNone;
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workWrite(Request *req)
+{
+#if 0
+ // NYI: Coming soon
+ auto hdr = req->header();
+
+ // look up session
+ auto session = getSession(hdr->session);
+ if (session == nullptr) {
+ return kErrNoSession;
+ }
+
+ // append to file
+ int result = session->append(hdr->offset, &hdr->data[0], hdr->size);
+
+ if (result < 0) {
+ // XXX might also be no space, I/O, etc.
+ return kErrNotAppend;
+ }
+
+ hdr->size = result;
+ return kErrNone;
+#else
+ return kErrPerm;
+#endif
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRemove(Request *req)
+{
+ //auto hdr = req->header();
+
+ // for now, send error reply
+ return kErrPerm;
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workTerminate(Request *req)
+{
+ auto hdr = req->header();
+
+ if (!_validSession(hdr->session)) {
+ return kErrNoSession;
+ }
+
+ ::close(_session_fds[hdr->session]);
+
+ return kErrNone;
+}
+
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workReset(void)
+{
+ for (size_t i=0; i<kMaxSession; i++) {
+ if (_session_fds[i] != -1) {
+ ::close(_session_fds[i]);
+ _session_fds[i] = -1;
+ }
+ }
+
+ return kErrNone;
+}
+
+bool
+MavlinkFTP::_validSession(unsigned index)
+{
+ if ((index >= kMaxSession) || (_session_fds[index] < 0)) {
+ return false;
+ }
+ return true;
+}
+
+int
+MavlinkFTP::_findUnusedSession(void)
+{
+ for (size_t i=0; i<kMaxSession; i++) {
+ if (_session_fds[i] == -1) {
+ return i;
+ }
+ }
+
+ return -1;
+}
+
+char *
+MavlinkFTP::Request::dataAsCString()
+{
+ // guarantee nul termination
+ if (header()->size < kMaxDataLength) {
+ requestData()[header()->size] = '\0';
+ } else {
+ requestData()[kMaxDataLength - 1] = '\0';
+ }
+
+ // and return data
+ return (char *)&(header()->data[0]);
+}
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
new file mode 100644
index 000000000..59237a4c4
--- /dev/null
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -0,0 +1,227 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+/**
+ * @file mavlink_ftp.h
+ *
+ * MAVLink remote file server.
+ *
+ * Messages are wrapped in ENCAPSULATED_DATA messages. Every message includes
+ * a session ID and sequence number.
+ *
+ * A limited number of requests (currently 2) may be outstanding at a time.
+ * Additional messages will be discarded.
+ *
+ * Messages consist of a fixed header, followed by a data area.
+ *
+ */
+
+#include <dirent.h>
+#include <queue.h>
+
+#include <nuttx/wqueue.h>
+#include <systemlib/err.h>
+
+#include "mavlink_messages.h"
+
+class MavlinkFTP
+{
+public:
+ MavlinkFTP();
+
+ static MavlinkFTP *getServer();
+
+ // static interface
+ void handle_message(Mavlink* mavlink,
+ mavlink_message_t *msg);
+
+private:
+
+ static const unsigned kRequestQueueSize = 2;
+
+ static MavlinkFTP *_server;
+
+ struct RequestHeader
+ {
+ uint8_t magic;
+ uint8_t session;
+ uint8_t opcode;
+ uint8_t size;
+ uint32_t crc32;
+ uint32_t offset;
+ uint8_t data[];
+ };
+
+ enum Opcode : uint8_t
+ {
+ kCmdNone, // ignored, always acked
+ kCmdTerminate, // releases sessionID, closes file
+ kCmdReset, // terminates all sessions
+ kCmdList, // list files in <path> from <offset>
+ kCmdOpen, // opens <path> for reading, returns <session>
+ kCmdRead, // reads <size> bytes from <offset> in <session>
+ kCmdCreate, // creates <path> for writing, returns <session>
+ kCmdWrite, // appends <size> bytes at <offset> in <session>
+ kCmdRemove, // remove file (only if created by server?)
+
+ kRspAck,
+ kRspNak
+ };
+
+ enum ErrorCode : uint8_t
+ {
+ kErrNone,
+ kErrNoRequest,
+ kErrNoSession,
+ kErrSequence,
+ kErrNotDir,
+ kErrNotFile,
+ kErrEOF,
+ kErrNotAppend,
+ kErrTooBig,
+ kErrIO,
+ kErrPerm
+ };
+
+ int _findUnusedSession(void);
+ bool _validSession(unsigned index);
+
+ static const unsigned kMaxSession = 2;
+ int _session_fds[kMaxSession];
+
+ class Request
+ {
+ public:
+ union {
+ dq_entry_t entry;
+ work_s work;
+ };
+
+ bool decode(Mavlink *mavlink, mavlink_message_t *fromMessage) {
+ if (fromMessage->msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA) {
+ _mavlink = mavlink;
+ mavlink_msg_encapsulated_data_decode(fromMessage, &_message);
+ return true;
+ }
+ return false;
+ }
+
+ void reply() {
+
+ // XXX the proper way would be an IOCTL / uORB call, rather than exploiting the
+ // flat memory architecture, as we're operating between threads here.
+ mavlink_message_t msg;
+ msg.checksum = 0;
+ unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
+ _mavlink->get_channel(), &msg, sequence(), rawData());
+
+ _mavlink->lockMessageBufferMutex();
+ bool success = _mavlink->message_buffer_write(&msg, len);
+ _mavlink->unlockMessageBufferMutex();
+
+ if (!success) {
+ warnx("FTP TX ERR");
+ }
+ // else {
+ // warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
+ // _mavlink->get_system_id(),
+ // _mavlink->get_component_id(),
+ // _mavlink->get_channel(),
+ // len,
+ // msg.checksum);
+ // }
+ }
+
+ uint8_t *rawData() { return &_message.data[0]; }
+ RequestHeader *header() { return reinterpret_cast<RequestHeader *>(&_message.data[0]); }
+ uint8_t *requestData() { return &(header()->data[0]); }
+ unsigned dataSize() { return header()->size + sizeof(RequestHeader); }
+ uint16_t sequence() const { return _message.seqnr; }
+ mavlink_channel_t channel() { return _mavlink->get_channel(); }
+
+ char *dataAsCString();
+
+ private:
+ Mavlink *_mavlink;
+ mavlink_encapsulated_data_t _message;
+
+ };
+
+ static const uint8_t kProtocolMagic = 'f';
+ static const char kDirentFile = 'F';
+ static const char kDirentDir = 'D';
+ static const char kDirentUnknown = 'U';
+ static const uint8_t kMaxDataLength = MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN - sizeof(RequestHeader);
+
+ /// Request worker; runs on the low-priority work queue to service
+ /// remote requests.
+ ///
+ static void _workerTrampoline(void *arg);
+ void _worker(Request *req);
+
+ /// Reply to a request (XXX should be a Request method)
+ ///
+ void _reply(Request *req);
+
+ ErrorCode _workList(Request *req);
+ ErrorCode _workOpen(Request *req, bool create);
+ ErrorCode _workRead(Request *req);
+ ErrorCode _workWrite(Request *req);
+ ErrorCode _workRemove(Request *req);
+ ErrorCode _workTerminate(Request *req);
+ ErrorCode _workReset();
+
+ // work freelist
+ Request _workBufs[kRequestQueueSize];
+ dq_queue_t _workFree;
+ sem_t _lock;
+
+ void _qLock() { do {} while (sem_wait(&_lock) != 0); }
+ void _qUnlock() { sem_post(&_lock); }
+
+ void _qFree(Request *req) {
+ _qLock();
+ dq_addlast(&req->entry, &_workFree);
+ _qUnlock();
+ }
+
+ Request *_dqFree() {
+ _qLock();
+ auto req = reinterpret_cast<Request *>(dq_remfirst(&_workFree));
+ _qUnlock();
+ return req;
+ }
+
+};
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index e300be074..cd0581af4 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -18,7 +18,6 @@
*
* 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,
@@ -73,8 +72,6 @@
#include <mavlink/mavlink_log.h>
#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/mission.h>
-#include <uORB/topics/mission_result.h>
#include "mavlink_bridge_header.h"
#include "mavlink_main.h"
@@ -83,6 +80,10 @@
#include "mavlink_rate_limiter.h"
#include "mavlink_commands.h"
+#ifndef MAVLINK_CRC_EXTRA
+ #error MAVLINK_CRC_EXTRA has to be defined on PX4 systems
+#endif
+
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
@@ -105,6 +106,8 @@ static struct file_operations fops;
*/
extern "C" __EXPORT int mavlink_main(int argc, char *argv[]);
+extern mavlink_system_t mavlink_system;
+
static uint64_t last_write_success_times[6] = {0};
static uint64_t last_write_try_times[6] = {0};
@@ -114,6 +117,7 @@ static uint64_t last_write_try_times[6] = {0};
void
mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length)
{
+
Mavlink *instance;
switch (channel) {
@@ -192,20 +196,18 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
if (buf_free < desired) {
/* we don't want to send anything just in half, so return */
+ instance->count_txerr();
return;
}
}
ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
- warnx("TX FAIL");
+ instance->count_txerr();
} else {
last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel];
}
}
-
-
-
}
static void usage(void);
@@ -224,23 +226,31 @@ Mavlink::Mavlink() :
_main_loop_delay(1000),
_subscriptions(nullptr),
_streams(nullptr),
+ _mission_manager(nullptr),
_mission_pub(-1),
+ _mission_result_sub(-1),
_mode(MAVLINK_MODE_NORMAL),
_total_counter(0),
_verbose(false),
_forwarding_on(false),
_passing_on(false),
+ _ftp_on(false),
_uart_fd(-1),
_mavlink_param_queue_index(0),
_subscribe_to_stream(nullptr),
_subscribe_to_stream_rate(0.0f),
_flow_control_enabled(true),
_message_buffer({}),
+ _param_initialized(false),
+ _param_system_id(0),
+ _param_component_id(0),
+ _param_system_type(0),
+ _param_use_hil_gps(0),
+
/* performance counters */
- _loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
+ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")),
+ _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe"))
{
- _wpm = &_wpm_s;
- mission.count = 0;
fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl;
_instance_id = Mavlink::instance_count();
@@ -290,6 +300,7 @@ Mavlink::Mavlink() :
Mavlink::~Mavlink()
{
perf_free(_loop_perf);
+ perf_free(_txerr_perf);
if (_task_running) {
/* task wakes up every 10ms or so at the longest */
@@ -315,6 +326,12 @@ Mavlink::~Mavlink()
}
void
+Mavlink::count_txerr()
+{
+ perf_count(_txerr_perf);
+}
+
+void
Mavlink::set_mode(enum MAVLINK_MODE mode)
{
_mode = mode;
@@ -418,7 +435,7 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self)
}
void
-Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self)
+Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
{
Mavlink *inst;
@@ -475,6 +492,7 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg)
// printf("logmsg: %s\n", txt);
struct mavlink_logmessage msg;
strncpy(msg.text, txt, sizeof(msg.text));
+ msg.severity = (unsigned char)cmd;
Mavlink *inst;
LL_FOREACH(_mavlink_instances, inst) {
@@ -494,48 +512,52 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg)
void Mavlink::mavlink_update_system(void)
{
- static bool initialized = false;
- static param_t param_system_id;
- static param_t param_component_id;
- static param_t param_system_type;
- static param_t param_use_hil_gps;
-
- if (!initialized) {
- param_system_id = param_find("MAV_SYS_ID");
- param_component_id = param_find("MAV_COMP_ID");
- param_system_type = param_find("MAV_TYPE");
- param_use_hil_gps = param_find("MAV_USEHILGPS");
- initialized = true;
+ if (!_param_initialized) {
+ _param_system_id = param_find("MAV_SYS_ID");
+ _param_component_id = param_find("MAV_COMP_ID");
+ _param_system_type = param_find("MAV_TYPE");
+ _param_use_hil_gps = param_find("MAV_USEHILGPS");
+ _param_initialized = true;
}
/* update system and component id */
int32_t system_id;
- param_get(param_system_id, &system_id);
+ param_get(_param_system_id, &system_id);
if (system_id > 0 && system_id < 255) {
mavlink_system.sysid = system_id;
}
int32_t component_id;
- param_get(param_component_id, &component_id);
+ param_get(_param_component_id, &component_id);
if (component_id > 0 && component_id < 255) {
mavlink_system.compid = component_id;
}
int32_t system_type;
- param_get(param_system_type, &system_type);
+ param_get(_param_system_type, &system_type);
if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) {
mavlink_system.type = system_type;
}
int32_t use_hil_gps;
- param_get(param_use_hil_gps, &use_hil_gps);
+ param_get(_param_use_hil_gps, &use_hil_gps);
_use_hil_gps = (bool)use_hil_gps;
}
+int Mavlink::get_system_id()
+{
+ return mavlink_system.sysid;
+}
+
+int Mavlink::get_component_id()
+{
+ return mavlink_system.compid;
+}
+
int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios *uart_config_original, bool *is_usb)
{
/* process baud rate */
@@ -703,9 +725,32 @@ Mavlink::set_hil_enabled(bool hil_enabled)
return ret;
}
-extern mavlink_system_t mavlink_system;
+void
+Mavlink::send_message(const mavlink_message_t *msg)
+{
+ uint8_t buf[MAVLINK_MAX_PACKET_LEN];
+
+ uint16_t len = mavlink_msg_to_send_buffer(buf, msg);
+ mavlink_send_uart_bytes(_channel, buf, len);
+}
-int Mavlink::mavlink_pm_queued_send()
+void
+Mavlink::handle_message(const mavlink_message_t *msg)
+{
+ /* handle packet with mission manager */
+ _mission_manager->handle_message(msg);
+
+ /* handle packet with parameter component */
+ mavlink_pm_message_handler(_channel, msg);
+
+ if (get_forwarding_on()) {
+ /* forward any messages to other mavlink instances */
+ Mavlink::forward_message(msg, this);
+ }
+}
+
+int
+Mavlink::mavlink_pm_queued_send()
{
if (_mavlink_param_queue_index < param_count()) {
mavlink_pm_send_param(param_for_index(_mavlink_param_queue_index));
@@ -782,7 +827,7 @@ int Mavlink::mavlink_pm_send_param(param_t param)
mavlink_type,
param_count(),
param_get_index(param));
- mavlink_missionlib_send_message(&tx_msg);
+ send_message(&tx_msg);
return OK;
}
@@ -796,7 +841,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav
(req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) {
/* Start sending parameters */
mavlink_pm_start_queued_send();
- mavlink_missionlib_send_gcs_string("[mavlink pm] sending list");
+ send_statustext_info("[pm] sending list");
}
} break;
@@ -819,8 +864,8 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav
if (param == PARAM_INVALID) {
char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN];
- sprintf(buf, "[mavlink pm] unknown: %s", name);
- mavlink_missionlib_send_gcs_string(buf);
+ sprintf(buf, "[pm] unknown: %s", name);
+ send_statustext_info(buf);
} else {
/* set and send parameter */
@@ -856,677 +901,29 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav
}
}
-void Mavlink::publish_mission()
-{
- /* Initialize mission publication if necessary */
- if (_mission_pub < 0) {
- _mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
-
- } else {
- orb_publish(ORB_ID(offboard_mission), _mission_pub, &mission);
- }
-}
-
-int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item)
-{
- /* only support global waypoints for now */
- switch (mavlink_mission_item->frame) {
- case MAV_FRAME_GLOBAL:
- mission_item->lat = (double)mavlink_mission_item->x;
- mission_item->lon = (double)mavlink_mission_item->y;
- mission_item->altitude = mavlink_mission_item->z;
- mission_item->altitude_is_relative = false;
- break;
-
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- mission_item->lat = (double)mavlink_mission_item->x;
- mission_item->lon = (double)mavlink_mission_item->y;
- mission_item->altitude = mavlink_mission_item->z;
- mission_item->altitude_is_relative = true;
- break;
-
- case MAV_FRAME_LOCAL_NED:
- case MAV_FRAME_LOCAL_ENU:
- return MAV_MISSION_UNSUPPORTED_FRAME;
-
- case MAV_FRAME_MISSION:
- default:
- return MAV_MISSION_ERROR;
- }
-
- switch (mavlink_mission_item->command) {
- case MAV_CMD_NAV_TAKEOFF:
- mission_item->pitch_min = mavlink_mission_item->param1;
- break;
-
- default:
- mission_item->acceptance_radius = mavlink_mission_item->param2;
- mission_item->time_inside = mavlink_mission_item->param1;
- break;
- }
-
- mission_item->yaw = _wrap_pi(mavlink_mission_item->param4 * M_DEG_TO_RAD_F);
- mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
- mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
- mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
-
- mission_item->autocontinue = mavlink_mission_item->autocontinue;
- // mission_item->index = mavlink_mission_item->seq;
- mission_item->origin = ORIGIN_MAVLINK;
-
- return OK;
-}
-
-int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
-{
- if (mission_item->altitude_is_relative) {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
-
- } else {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
- }
-
- switch (mission_item->nav_cmd) {
- case NAV_CMD_TAKEOFF:
- mavlink_mission_item->param1 = mission_item->pitch_min;
- break;
-
- default:
- mavlink_mission_item->param2 = mission_item->acceptance_radius;
- mavlink_mission_item->param1 = mission_item->time_inside;
- break;
- }
-
- mavlink_mission_item->x = (float)mission_item->lat;
- mavlink_mission_item->y = (float)mission_item->lon;
- mavlink_mission_item->z = mission_item->altitude;
-
- mavlink_mission_item->param4 = mission_item->yaw * M_RAD_TO_DEG_F;
- mavlink_mission_item->param3 = mission_item->loiter_radius * (float)mission_item->loiter_direction;
- mavlink_mission_item->command = mission_item->nav_cmd;
- mavlink_mission_item->autocontinue = mission_item->autocontinue;
- // mavlink_mission_item->seq = mission_item->index;
-
- return OK;
-}
-
-void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state)
-{
- state->size = 0;
- state->max_size = MAVLINK_WPM_MAX_WP_COUNT;
- state->current_state = MAVLINK_WPM_STATE_IDLE;
- state->current_partner_sysid = 0;
- state->current_partner_compid = 0;
- state->timestamp_lastaction = 0;
- state->timestamp_last_send_setpoint = 0;
- state->timestamp_last_send_request = 0;
- state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT;
- state->current_dataman_id = 0;
-}
-
-/*
- * @brief Sends an waypoint ack message
- */
-void Mavlink::mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type)
-{
- mavlink_message_t msg;
- mavlink_mission_ack_t wpa;
-
- wpa.target_system = sysid;
- wpa.target_component = compid;
- wpa.type = type;
-
- mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpa);
- mavlink_missionlib_send_message(&msg);
-
- if (_verbose) { warnx("Sent waypoint ack (%u) to ID %u", wpa.type, wpa.target_system); }
-}
-
-/*
- * @brief Broadcasts the new target waypoint and directs the MAV to fly there
- *
- * This function broadcasts its new active waypoint sequence number and
- * sends a message to the controller, advising it to fly to the coordinates
- * of the waypoint with a given orientation
- *
- * @param seq The waypoint sequence number the MAV should fly to.
- */
-void Mavlink::mavlink_wpm_send_waypoint_current(uint16_t seq)
-{
- if (seq < _wpm->size) {
- mavlink_message_t msg;
- mavlink_mission_current_t wpc;
-
- wpc.seq = seq;
-
- mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc);
- mavlink_missionlib_send_message(&msg);
-
- } else if (seq == 0 && _wpm->size == 0) {
-
- /* don't broadcast if no WPs */
-
- } else {
- mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds");
-
- if (_verbose) { warnx("ERROR: index out of bounds"); }
- }
-}
-
-void Mavlink::mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count)
-{
- mavlink_message_t msg;
- mavlink_mission_count_t wpc;
-
- wpc.target_system = sysid;
- wpc.target_component = compid;
- wpc.count = mission.count;
-
- mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc);
- mavlink_missionlib_send_message(&msg);
-
- if (_verbose) { warnx("Sent waypoint count (%u) to ID %u", wpc.count, wpc.target_system); }
-}
-
-void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq)
-{
-
- struct mission_item_s mission_item;
- ssize_t len = sizeof(struct mission_item_s);
-
- dm_item_t dm_current;
-
- if (_wpm->current_dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
-
- } else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
- }
-
- if (dm_read(dm_current, seq, &mission_item, len) == len) {
-
- /* create mission_item_s from mavlink_mission_item_t */
- mavlink_mission_item_t wp;
- map_mission_item_to_mavlink_mission_item(&mission_item, &wp);
-
- mavlink_message_t msg;
- wp.target_system = sysid;
- wp.target_component = compid;
- wp.seq = seq;
- mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp);
- mavlink_missionlib_send_message(&msg);
-
- if (_verbose) { warnx("Sent waypoint %u to ID %u", wp.seq, wp.target_system); }
-
- } else {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
- mavlink_missionlib_send_gcs_string("#audio: Unable to read from micro SD");
-
- if (_verbose) { warnx("ERROR: could not read WP%u", seq); }
- }
-}
-
-void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq)
-{
- if (seq < _wpm->max_size) {
- mavlink_message_t msg;
- mavlink_mission_request_t wpr;
- wpr.target_system = sysid;
- wpr.target_component = compid;
- wpr.seq = seq;
- mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpr);
- mavlink_missionlib_send_message(&msg);
- _wpm->timestamp_last_send_request = hrt_absolute_time();
-
- if (_verbose) { warnx("Sent waypoint request %u to ID %u", wpr.seq, wpr.target_system); }
-
- } else {
- mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity");
-
- if (_verbose) { warnx("ERROR: Waypoint index exceeds list capacity"); }
- }
-}
-
-/*
- * @brief emits a message that a waypoint reached
- *
- * This function broadcasts a message that a waypoint is reached.
- *
- * @param seq The waypoint sequence number the MAV has reached.
- */
-void Mavlink::mavlink_wpm_send_waypoint_reached(uint16_t seq)
-{
- mavlink_message_t msg;
- mavlink_mission_item_reached_t wp_reached;
-
- wp_reached.seq = seq;
-
- mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp_reached);
- mavlink_missionlib_send_message(&msg);
-
- if (_verbose) { warnx("Sent waypoint %u reached message", wp_reached.seq); }
-}
-
-void Mavlink::mavlink_waypoint_eventloop(uint64_t now)
+int
+Mavlink::send_statustext_info(const char *string)
{
- /* check for timed-out operations */
- if (now - _wpm->timestamp_lastaction > _wpm->timeout && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) {
-
- mavlink_missionlib_send_gcs_string("Operation timeout");
-
- if (_verbose) { warnx("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_state); }
-
- _wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- _wpm->current_partner_sysid = 0;
- _wpm->current_partner_compid = 0;
-
- } else if (now - _wpm->timestamp_last_send_request > 500000 && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
- /* try to get WP again after short timeout */
- mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
- }
+ return send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string);
}
-
-void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
+int
+Mavlink::send_statustext_critical(const char *string)
{
- uint64_t now = hrt_absolute_time();
-
- switch (msg->msgid) {
-
- case MAVLINK_MSG_ID_MISSION_ACK: {
- mavlink_mission_ack_t wpa;
- mavlink_msg_mission_ack_decode(msg, &wpa);
-
- if ((msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid) && (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/)) {
- _wpm->timestamp_lastaction = now;
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
- if (_wpm->current_wp_id == _wpm->size - 1) {
-
- _wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- _wpm->current_wp_id = 0;
- }
- }
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch");
-
- if (_verbose) { warnx("REJ. WP CMD: curr partner id mismatch"); }
- }
-
- break;
- }
-
- case MAVLINK_MSG_ID_MISSION_SET_CURRENT: {
- mavlink_mission_set_current_t wpc;
- mavlink_msg_mission_set_current_decode(msg, &wpc);
-
- if (wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) {
- _wpm->timestamp_lastaction = now;
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
- if (wpc.seq < _wpm->size) {
-
- mission.current_index = wpc.seq;
- publish_mission();
-
- /* don't answer yet, wait for the navigator to respond, then publish the mission_result */
-// mavlink_wpm_send_waypoint_current(wpc.seq);
-
- } else {
- mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list");
-
- if (_verbose) { warnx("IGN WP CURR CMD: Not in list"); }
- }
-
- } else {
- mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy");
-
- if (_verbose) { warnx("IGN WP CURR CMD: Busy"); }
-
- }
- }
-
- break;
- }
-
- case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: {
- mavlink_mission_request_list_t wprl;
- mavlink_msg_mission_request_list_decode(msg, &wprl);
-
- if (wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) {
- _wpm->timestamp_lastaction = now;
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
- if (_wpm->size > 0) {
-
- _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST;
- _wpm->current_wp_id = 0;
- _wpm->current_partner_sysid = msg->sysid;
- _wpm->current_partner_compid = msg->compid;
-
- } else {
- if (_verbose) { warnx("No waypoints send"); }
- }
-
- _wpm->current_count = _wpm->size;
- mavlink_wpm_send_waypoint_count(msg->sysid, msg->compid, _wpm->current_count);
-
- } else {
- mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy");
-
- if (_verbose) { warnx("IGN REQUEST LIST: Busy"); }
- }
- }
-
- break;
- }
-
- case MAVLINK_MSG_ID_MISSION_REQUEST: {
- mavlink_mission_request_t wpr;
- mavlink_msg_mission_request_decode(msg, &wpr);
-
- if (msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) {
- _wpm->timestamp_lastaction = now;
-
- if (wpr.seq >= _wpm->size) {
-
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list");
-
- if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.", wpr.seq); }
-
- break;
- }
-
- /*
- * Ensure that we are in the correct state and that the first request has id 0
- * and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint)
- */
- if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) {
-
- if (wpr.seq == 0) {
- if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
-
- _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0");
-
- if (_verbose) { warnx("REJ. WP CMD: First id != 0"); }
-
- break;
- }
-
- } else if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) {
-
- if (wpr.seq == _wpm->current_wp_id) {
-
- if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
-
- } else if (wpr.seq == _wpm->current_wp_id + 1) {
-
- if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); }
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
-
- if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).", wpr.seq, _wpm->current_wp_id, _wpm->current_wp_id + 1); }
-
- break;
- }
-
- } else {
-
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-
- if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).", _wpm->current_state); }
-
- break;
- }
-
- _wpm->current_wp_id = wpr.seq;
- _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS;
-
- if (wpr.seq < _wpm->size) {
-
- mavlink_wpm_send_waypoint(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
-
- } else {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
-
- if (_verbose) { warnx("ERROR: Waypoint %u out of bounds", wpr.seq); }
- }
-
-
- } else {
- //we we're target but already communicating with someone else
- if ((wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid)) {
-
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-
- if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.", msg->sysid, _wpm->current_partner_sysid); }
- }
- }
-
- break;
- }
-
- case MAVLINK_MSG_ID_MISSION_COUNT: {
- mavlink_mission_count_t wpc;
- mavlink_msg_mission_count_decode(msg, &wpc);
-
- if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) {
- _wpm->timestamp_lastaction = now;
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
-
- if (wpc.count > NUM_MISSIONS_SUPPORTED) {
- if (_verbose) { warnx("Too many waypoints: %d, supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED); }
-
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_NO_SPACE);
- break;
- }
-
- if (wpc.count == 0) {
- mavlink_missionlib_send_gcs_string("COUNT 0");
-
- if (_verbose) { warnx("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE"); }
-
- break;
- }
-
- if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); }
-
- _wpm->current_state = MAVLINK_WPM_STATE_GETLIST;
- _wpm->current_wp_id = 0;
- _wpm->current_partner_sysid = msg->sysid;
- _wpm->current_partner_compid = msg->compid;
- _wpm->current_count = wpc.count;
-
- mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
-
- } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
-
- if (_wpm->current_wp_id == 0) {
- mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN");
-
- if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u", wpc.count, msg->sysid); }
-
- } else {
- mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy");
-
- if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.", _wpm->current_wp_id); }
- }
-
- } else {
- mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy");
-
- if (_verbose) { warnx("IGN MISSION_COUNT CMD: Busy"); }
- }
- }
- }
- break;
-
- case MAVLINK_MSG_ID_MISSION_ITEM: {
- mavlink_mission_item_t wp;
- mavlink_msg_mission_item_decode(msg, &wp);
-
- if (wp.target_system == mavlink_system.sysid && wp.target_component == _mavlink_wpm_comp_id) {
-
- _wpm->timestamp_lastaction = now;
-
- /*
- * ensure that we are in the correct state and that the first waypoint has id 0
- * and the following waypoints have the correct ids
- */
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) {
-
- if (wp.seq != 0) {
- mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP not 0");
- warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.", wp.seq);
- break;
- }
-
- } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
-
- if (wp.seq >= _wpm->current_count) {
- mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds");
- warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.", wp.seq);
- break;
- }
-
- if (wp.seq != _wpm->current_wp_id) {
- warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.", wp.seq, _wpm->current_wp_id);
- mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
- break;
- }
- }
-
- _wpm->current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS;
-
- struct mission_item_s mission_item;
-
- int ret = map_mavlink_mission_item_to_mission_item(&wp, &mission_item);
-
- if (ret != OK) {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, ret);
- _wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- break;
- }
-
- ssize_t len = sizeof(struct mission_item_s);
-
- dm_item_t dm_next;
-
- if (_wpm->current_dataman_id == 0) {
- dm_next = DM_KEY_WAYPOINTS_OFFBOARD_1;
- mission.dataman_id = 1;
-
- } else {
- dm_next = DM_KEY_WAYPOINTS_OFFBOARD_0;
- mission.dataman_id = 0;
- }
-
- if (dm_write(dm_next, wp.seq, DM_PERSIST_IN_FLIGHT_RESET, &mission_item, len) != len) {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
- mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD");
- _wpm->current_state = MAVLINK_WPM_STATE_IDLE;
- break;
- }
-
-// if (wp.current) {
-// warnx("current is: %d", wp.seq);
-// mission.current_index = wp.seq;
-// }
- // XXX ignore current set
- mission.current_index = -1;
-
- _wpm->current_wp_id = wp.seq + 1;
-
- if (_wpm->current_wp_id == _wpm->current_count && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) {
-
- if (_verbose) { warnx("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_count); }
-
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
-
- mission.count = _wpm->current_count;
-
- publish_mission();
-
- _wpm->current_dataman_id = mission.dataman_id;
- _wpm->size = _wpm->current_count;
-
- _wpm->current_state = MAVLINK_WPM_STATE_IDLE;
-
- } else {
- mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id);
- }
- }
-
- break;
- }
-
- case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: {
- mavlink_mission_clear_all_t wpca;
- mavlink_msg_mission_clear_all_decode(msg, &wpca);
-
- if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) {
-
- if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) {
- _wpm->timestamp_lastaction = now;
-
- _wpm->size = 0;
-
- /* prepare mission topic */
- mission.dataman_id = -1;
- mission.count = 0;
- mission.current_index = -1;
- publish_mission();
-
- if (dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_0) == OK && dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_1) == OK) {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED);
-
- } else {
- mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR);
- }
-
-
- } else {
- mavlink_missionlib_send_gcs_string("IGN WP CLEAR CMD: Busy");
-
- if (_verbose) { warnx("IGN WP CLEAR CMD: Busy"); }
- }
- }
-
- break;
- }
-
- default: {
- /* other messages might should get caught by mavlink and others */
- break;
- }
- }
+ return send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string);
}
-void
-Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
+int
+Mavlink::send_statustext_emergency(const char *string)
{
- uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
-
- uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
-
- mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len);
+ return send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string);
}
-
-
int
-Mavlink::mavlink_missionlib_send_gcs_string(const char *string)
+Mavlink::send_statustext(unsigned severity, const char *string)
{
const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
mavlink_statustext_t statustext;
- statustext.severity = MAV_SEVERITY_INFO;
int i = 0;
@@ -1544,11 +941,24 @@ Mavlink::mavlink_missionlib_send_gcs_string(const char *string)
/* Enforce null termination */
statustext.text[i] = '\0';
+ /* Map severity */
+ switch (severity) {
+ case MAVLINK_IOC_SEND_TEXT_INFO:
+ statustext.severity = MAV_SEVERITY_INFO;
+ break;
+ case MAVLINK_IOC_SEND_TEXT_CRITICAL:
+ statustext.severity = MAV_SEVERITY_CRITICAL;
+ break;
+ case MAVLINK_IOC_SEND_TEXT_EMERGENCY:
+ statustext.severity = MAV_SEVERITY_EMERGENCY;
+ break;
+ }
+
mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text);
return OK;
} else {
- return 1;
+ return ERROR;
}
}
@@ -1590,31 +1000,36 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
/* delete stream */
LL_DELETE(_streams, stream);
delete stream;
+ warnx("deleted stream %s", stream->get_name());
}
return OK;
}
}
- if (interval > 0) {
- /* search for stream with specified name in supported streams list */
- for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
- if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
- /* create new instance */
- stream = streams_list[i]->new_instance();
- stream->set_channel(get_channel());
- stream->set_interval(interval);
- stream->subscribe(this);
- LL_APPEND(_streams, stream);
- return OK;
- }
- }
-
- } else {
- /* stream not found, nothing to disable */
+ if (interval == 0) {
+ /* stream was not active and is requested to be disabled, do nothing */
return OK;
}
+ /* search for stream with specified name in supported streams list */
+ for (unsigned int i = 0; streams_list[i] != nullptr; i++) {
+
+ if (strcmp(stream_name, streams_list[i]->get_name()) == 0) {
+ /* create new instance */
+ stream = streams_list[i]->new_instance();
+ stream->set_channel(get_channel());
+ stream->set_interval(interval);
+ stream->subscribe(this);
+ LL_APPEND(_streams, stream);
+
+ return OK;
+ }
+ }
+
+ /* if we reach here, the stream list does not contain the stream */
+ warnx("stream %s not found", stream_name);
+
return ERROR;
}
@@ -1649,11 +1064,21 @@ Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate)
int
Mavlink::message_buffer_init(int size)
{
+
_message_buffer.size = size;
_message_buffer.write_ptr = 0;
_message_buffer.read_ptr = 0;
_message_buffer.data = (char*)malloc(_message_buffer.size);
- return (_message_buffer.data == 0) ? ERROR : OK;
+
+ int ret;
+ if (_message_buffer.data == 0) {
+ ret = ERROR;
+ _message_buffer.size = 0;
+ } else {
+ ret = OK;
+ }
+
+ return ret;
}
void
@@ -1685,7 +1110,7 @@ Mavlink::message_buffer_is_empty()
bool
-Mavlink::message_buffer_write(void *ptr, int size)
+Mavlink::message_buffer_write(const void *ptr, int size)
{
// bytes available to write
int available = _message_buffer.read_ptr - _message_buffer.write_ptr - 1;
@@ -1752,7 +1177,7 @@ Mavlink::message_buffer_mark_read(int n)
}
void
-Mavlink::pass_message(mavlink_message_t *msg)
+Mavlink::pass_message(const mavlink_message_t *msg)
{
if (_passing_on) {
/* size is 8 bytes plus variable payload */
@@ -1763,7 +1188,11 @@ Mavlink::pass_message(mavlink_message_t *msg)
}
}
-
+float
+Mavlink::get_rate_mult()
+{
+ return _datarate / 1000.0f;
+}
int
Mavlink::task_main(int argc, char *argv[])
@@ -1781,7 +1210,7 @@ Mavlink::task_main(int argc, char *argv[])
* set error flag instead */
bool err_flag = false;
- while ((ch = getopt(argc, argv, "b:r:d:m:fpvw")) != EOF) {
+ while ((ch = getopt(argc, argv, "b:r:d:m:fpvwx")) != EOF) {
switch (ch) {
case 'b':
_baudrate = strtoul(optarg, NULL, 10);
@@ -1837,6 +1266,10 @@ Mavlink::task_main(int argc, char *argv[])
_wait_to_transmit = true;
break;
+ case 'x':
+ _ftp_on = true;
+ break;
+
default:
err_flag = true;
break;
@@ -1881,8 +1314,6 @@ Mavlink::task_main(int argc, char *argv[])
break;
}
- _mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER;
-
warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate);
/* flush stdout in case MAVLink is about to take it over */
@@ -1902,9 +1333,12 @@ Mavlink::task_main(int argc, char *argv[])
mavlink_logbuffer_init(&_logbuffer, 5);
/* if we are passing on mavlink messages, we need to prepare a buffer for this instance */
- if (_passing_on) {
- /* initialize message buffer if multiplexing is on */
- if (OK != message_buffer_init(500)) {
+ if (_passing_on || _ftp_on) {
+ /* initialize message buffer if multiplexing is on or its needed for FTP.
+ * make space for two messages plus off-by-one space as we use the empty element
+ * marker ring buffer approach.
+ */
+ if (OK != message_buffer_init(2 * MAVLINK_MAX_PACKET_LEN + 2)) {
errx(1, "can't allocate message buffer, exiting");
}
@@ -1924,24 +1358,26 @@ Mavlink::task_main(int argc, char *argv[])
/* start the MAVLink receiver */
_receive_thread = MavlinkReceiver::receive_start(this);
- /* initialize waypoint manager */
- mavlink_wpm_init(_wpm);
+ _mission_result_sub = orb_subscribe(ORB_ID(mission_result));
- int mission_result_sub = orb_subscribe(ORB_ID(mission_result));
- struct mission_result_s mission_result;
- memset(&mission_result, 0, sizeof(mission_result));
+ /* create mission manager */
+ _mission_manager = new MavlinkMissionManager(this);
+ _mission_manager->set_verbose(_verbose);
_task_running = true;
MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update));
+ uint64_t param_time = 0;
MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status));
+ uint64_t status_time = 0;
- struct vehicle_status_s *status = (struct vehicle_status_s *) status_sub->get_data();
+ struct vehicle_status_s status;
+ status_sub->update(&status_time, &status);
MavlinkCommandsStream commands_stream(this, _channel);
/* add default streams depending on mode and intervals depending on datarate */
- float rate_mult = _datarate / 1000.0f;
+ float rate_mult = get_rate_mult();
configure_stream("HEARTBEAT", 1.0f);
@@ -1976,7 +1412,6 @@ Mavlink::task_main(int argc, char *argv[])
/* don't send parameters on startup without request */
_mavlink_param_queue_index = param_count();
- MavlinkRateLimiter slow_rate_limiter(2000000.0f / rate_mult);
MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult);
/* set main loop delay depending on data rate to minimize CPU overhead */
@@ -1993,14 +1428,14 @@ Mavlink::task_main(int argc, char *argv[])
hrt_abstime t = hrt_absolute_time();
- if (param_sub->update(t)) {
+ if (param_sub->update(&param_time, nullptr)) {
/* parameters updated */
mavlink_update_system();
}
- if (status_sub->update(t)) {
+ if (status_sub->update(&status_time, &status)) {
/* switch HIL mode if required */
- set_hil_enabled(status->hil_state == HIL_STATE_ON);
+ set_hil_enabled(status.hil_state == HIL_STATE_ON);
}
/* update commands stream */
@@ -2030,74 +1465,72 @@ Mavlink::task_main(int argc, char *argv[])
stream->update(t);
}
- bool updated;
- orb_check(mission_result_sub, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result);
-
- if (_verbose) { warnx("Got mission result: new current: %d", mission_result.index_current_mission); }
-
- if (mission_result.mission_reached) {
- mavlink_wpm_send_waypoint_reached((uint16_t)mission_result.mission_index_reached);
- }
-
- mavlink_wpm_send_waypoint_current((uint16_t)mission_result.index_current_mission);
-
- } else {
- if (slow_rate_limiter.check(t)) {
- mavlink_wpm_send_waypoint_current((uint16_t)mission_result.index_current_mission);
- }
- }
-
if (fast_rate_limiter.check(t)) {
mavlink_pm_queued_send();
- mavlink_waypoint_eventloop(hrt_absolute_time());
+ _mission_manager->eventloop();
if (!mavlink_logbuffer_is_empty(&_logbuffer)) {
struct mavlink_logmessage msg;
int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg);
if (lb_ret == OK) {
- mavlink_missionlib_send_gcs_string(msg.text);
+ send_statustext(msg.severity, msg.text);
}
}
}
- /* pass messages from other UARTs */
- if (_passing_on) {
+ /* pass messages from other UARTs or FTP worker */
+ if (_passing_on || _ftp_on) {
bool is_part;
- void *read_ptr;
+ uint8_t *read_ptr;
+ uint8_t *write_ptr;
- /* guard get ptr by mutex */
pthread_mutex_lock(&_message_buffer_mutex);
- int available = message_buffer_get_ptr(&read_ptr, &is_part);
+ int available = message_buffer_get_ptr((void**)&read_ptr, &is_part);
pthread_mutex_unlock(&_message_buffer_mutex);
if (available > 0) {
- /* write first part of buffer */
- _mavlink_resend_uart(_channel, (const mavlink_message_t*)read_ptr);
- message_buffer_mark_read(available);
+ // Reconstruct message from buffer
+
+ mavlink_message_t msg;
+ write_ptr = (uint8_t*)&msg;
+
+ // Pull a single message from the buffer
+ size_t read_count = available;
+ if (read_count > sizeof(mavlink_message_t)) {
+ read_count = sizeof(mavlink_message_t);
+ }
+
+ memcpy(write_ptr, read_ptr, read_count);
+
+ // We hold the mutex until after we complete the second part of the buffer. If we don't
+ // we may end up breaking the empty slot overflow detection semantics when we mark the
+ // possibly partial read below.
+ pthread_mutex_lock(&_message_buffer_mutex);
+
+ message_buffer_mark_read(read_count);
/* write second part of buffer if there is some */
- if (is_part) {
- /* guard get ptr by mutex */
- pthread_mutex_lock(&_message_buffer_mutex);
- available = message_buffer_get_ptr(&read_ptr, &is_part);
- pthread_mutex_unlock(&_message_buffer_mutex);
-
- _mavlink_resend_uart(_channel, (const mavlink_message_t*)read_ptr);
+ if (is_part && read_count < sizeof(mavlink_message_t)) {
+ write_ptr += read_count;
+ available = message_buffer_get_ptr((void**)&read_ptr, &is_part);
+ read_count = sizeof(mavlink_message_t) - read_count;
+ memcpy(write_ptr, read_ptr, read_count);
message_buffer_mark_read(available);
}
+
+ pthread_mutex_unlock(&_message_buffer_mutex);
+
+ _mavlink_resend_uart(_channel, &msg);
}
}
-
-
perf_end(_loop_perf);
}
+ delete _mission_manager;
+
delete _subscribe_to_stream;
_subscribe_to_stream = nullptr;
@@ -2139,7 +1572,7 @@ Mavlink::task_main(int argc, char *argv[])
/* close mavlink logging device */
close(_mavlink_fd);
- if (_passing_on) {
+ if (_passing_on || _ftp_on) {
message_buffer_destroy();
pthread_mutex_destroy(&_message_buffer_mutex);
}
@@ -2157,11 +1590,20 @@ int Mavlink::start_helper(int argc, char *argv[])
/* create the instance in task context */
Mavlink *instance = new Mavlink();
- /* this will actually only return once MAVLink exits */
- int res = instance->task_main(argc, argv);
+ int res;
+
+ if (!instance) {
- /* delete instance on main thread end */
- delete instance;
+ /* out of memory */
+ res = -ENOMEM;
+ warnx("OUT OF MEM");
+ } else {
+ /* this will actually only return once MAVLink exits */
+ res = instance->task_main(argc, argv);
+
+ /* delete instance on main thread end */
+ delete instance;
+ }
return res;
}
@@ -2184,7 +1626,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 1950,
+ 2700,
(main_t)&Mavlink::start_helper,
(const char **)argv);
@@ -2212,13 +1654,13 @@ Mavlink::start(int argc, char *argv[])
}
void
-Mavlink::status()
+Mavlink::display_status()
{
warnx("running");
}
int
-Mavlink::stream(int argc, char *argv[])
+Mavlink::stream_command(int argc, char *argv[])
{
const char *device_name = DEFAULT_DEVICE_NAME;
float rate = -1.0f;
@@ -2281,7 +1723,7 @@ Mavlink::stream(int argc, char *argv[])
static void usage()
{
- warnx("usage: mavlink {start|stop-all|stream} [-d device] [-b baudrate] [-r rate] [-m mode] [-s stream] [-f] [-p] [-v] [-w]");
+ warnx("usage: mavlink {start|stop-all|stream} [-d device] [-b baudrate]\n\t[-r rate][-m mode] [-s stream] [-f] [-p] [-v] [-w] [-x]");
}
int mavlink_main(int argc, char *argv[])
@@ -2306,7 +1748,7 @@ int mavlink_main(int argc, char *argv[])
// mavlink::g_mavlink->status();
} else if (!strcmp(argv[1], "stream")) {
- return Mavlink::stream(argc, argv);
+ return Mavlink::stream_command(argc, argv);
} else {
usage();
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 40edc4b85..acfc8b90e 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -50,53 +50,13 @@
#include <uORB/uORB.h>
#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
#include "mavlink_bridge_header.h"
#include "mavlink_orb_subscription.h"
#include "mavlink_stream.h"
#include "mavlink_messages.h"
-
-// FIXME XXX - TO BE MOVED TO XML
-enum MAVLINK_WPM_STATES {
- MAVLINK_WPM_STATE_IDLE = 0,
- MAVLINK_WPM_STATE_SENDLIST,
- MAVLINK_WPM_STATE_SENDLIST_SENDWPS,
- MAVLINK_WPM_STATE_GETLIST,
- MAVLINK_WPM_STATE_GETLIST_GETWPS,
- MAVLINK_WPM_STATE_GETLIST_GOTALL,
- MAVLINK_WPM_STATE_ENUM_END
-};
-
-enum MAVLINK_WPM_CODES {
- MAVLINK_WPM_CODE_OK = 0,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
- MAVLINK_WPM_CODE_ENUM_END
-};
-
-
-#define MAVLINK_WPM_MAX_WP_COUNT 255
-#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds
-#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint
-#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000
-
-
-struct mavlink_wpm_storage {
- uint16_t size;
- uint16_t max_size;
- enum MAVLINK_WPM_STATES current_state;
- int16_t current_wp_id; ///< Waypoint in current transmission
- uint16_t current_count;
- uint8_t current_partner_sysid;
- uint8_t current_partner_compid;
- uint64_t timestamp_lastaction;
- uint64_t timestamp_last_send_setpoint;
- uint64_t timestamp_last_send_request;
- uint32_t timeout;
- int current_dataman_id;
-};
+#include "mavlink_mission.h"
class Mavlink
@@ -123,27 +83,41 @@ public:
/**
* Display the mavlink status.
*/
- void status();
+ void display_status();
- static int stream(int argc, char *argv[]);
+ static int stream_command(int argc, char *argv[]);
- static int instance_count();
+ static int instance_count();
- static Mavlink *new_instance();
+ static Mavlink *new_instance();
- static Mavlink *get_instance(unsigned instance);
+ static Mavlink *get_instance(unsigned instance);
- static Mavlink *get_instance_for_device(const char *device_name);
+ static Mavlink *get_instance_for_device(const char *device_name);
- static int destroy_all_instances();
+ static int destroy_all_instances();
- static bool instance_exists(const char *device_name, Mavlink *self);
+ static bool instance_exists(const char *device_name, Mavlink *self);
- static void forward_message(mavlink_message_t *msg, Mavlink *self);
+ static void forward_message(const mavlink_message_t *msg, Mavlink *self);
- static int get_uart_fd(unsigned index);
+ static int get_uart_fd(unsigned index);
- int get_uart_fd();
+ int get_uart_fd();
+
+ /**
+ * Get the MAVLink system id.
+ *
+ * @return The system ID of this vehicle
+ */
+ int get_system_id();
+
+ /**
+ * Get the MAVLink component id.
+ *
+ * @return The component ID of this vehicle
+ */
+ int get_component_id();
const char *_device_name;
@@ -153,30 +127,25 @@ public:
MAVLINK_MODE_CAMERA
};
- void set_mode(enum MAVLINK_MODE);
- enum MAVLINK_MODE get_mode() { return _mode; }
-
- bool get_hil_enabled() { return _hil_enabled; }
+ void set_mode(enum MAVLINK_MODE);
+ enum MAVLINK_MODE get_mode() { return _mode; }
- bool get_use_hil_gps() { return _use_hil_gps; }
+ bool get_hil_enabled() { return _hil_enabled; }
- bool get_flow_control_enabled() { return _flow_control_enabled; }
+ bool get_use_hil_gps() { return _use_hil_gps; }
- bool get_forwarding_on() { return _forwarding_on; }
+ bool get_flow_control_enabled() { return _flow_control_enabled; }
- /**
- * Handle waypoint related messages.
- */
- void mavlink_wpm_message_handler(const mavlink_message_t *msg);
+ bool get_forwarding_on() { return _forwarding_on; }
- static int start_helper(int argc, char *argv[]);
+ static int start_helper(int argc, char *argv[]);
/**
* Handle parameter related messages.
*/
- void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
+ void mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg);
- void get_mavlink_mode_and_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
+ void get_mavlink_mode_and_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
/**
* Enable / disable Hardware in the Loop simulation mode.
@@ -186,90 +155,135 @@ public:
* requested change could not be made or was
* redundant.
*/
- int set_hil_enabled(bool hil_enabled);
+ int set_hil_enabled(bool hil_enabled);
+
+ void send_message(const mavlink_message_t *msg);
+
+ void handle_message(const mavlink_message_t *msg);
MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic);
- int get_instance_id();
+ int get_instance_id();
/**
* Enable / disable hardware flow control.
*
* @param enabled True if hardware flow control should be enabled
*/
- int enable_flow_control(bool enabled);
+ int enable_flow_control(bool enabled);
+
+ mavlink_channel_t get_channel();
- mavlink_channel_t get_channel();
+ void configure_stream_threadsafe(const char *stream_name, float rate);
- bool _task_should_exit; /**< if true, mavlink task should exit */
+ bool _task_should_exit; /**< if true, mavlink task should exit */
- int get_mavlink_fd() { return _mavlink_fd; }
+ int get_mavlink_fd() { return _mavlink_fd; }
+ /**
+ * Send a status text with loglevel INFO
+ *
+ * @param string the message to send (will be capped by mavlink max string length)
+ */
+ int send_statustext_info(const char *string);
+
+ /**
+ * Send a status text with loglevel CRITICAL
+ *
+ * @param string the message to send (will be capped by mavlink max string length)
+ */
+ int send_statustext_critical(const char *string);
+
+ /**
+ * Send a status text with loglevel EMERGENCY
+ *
+ * @param string the message to send (will be capped by mavlink max string length)
+ */
+ int send_statustext_emergency(const char *string);
+
+ /**
+ * Send a status text with loglevel
+ *
+ * @param string the message to send (will be capped by mavlink max string length)
+ * @param severity the log level, one of
+ */
+ int send_statustext(unsigned severity, const char *string);
+ MavlinkStream * get_streams() const { return _streams; }
+
+ float get_rate_mult();
/* Functions for waiting to start transmission until message received. */
- void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
- bool get_has_received_messages() { return _received_messages; }
- void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
- bool get_wait_to_transmit() { return _wait_to_transmit; }
- bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
+ void set_has_received_messages(bool received_messages) { _received_messages = received_messages; }
+ bool get_has_received_messages() { return _received_messages; }
+ void set_wait_to_transmit(bool wait) { _wait_to_transmit = wait; }
+ bool get_wait_to_transmit() { return _wait_to_transmit; }
+ bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
+
+ bool message_buffer_write(const void *ptr, int size);
+
+ void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
+ void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
+
+ /**
+ * Count a transmision error
+ */
+ void count_txerr();
protected:
- Mavlink *next;
+ Mavlink *next;
private:
- int _instance_id;
+ int _instance_id;
- int _mavlink_fd;
- bool _task_running;
+ int _mavlink_fd;
+ bool _task_running;
/* states */
- bool _hil_enabled; /**< Hardware In the Loop mode */
- bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
- bool _is_usb_uart; /**< Port is USB */
- bool _wait_to_transmit; /**< Wait to transmit until received messages. */
- bool _received_messages; /**< Whether we've received valid mavlink messages. */
+ bool _hil_enabled; /**< Hardware In the Loop mode */
+ bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
+ bool _is_usb_uart; /**< Port is USB */
+ bool _wait_to_transmit; /**< Wait to transmit until received messages. */
+ bool _received_messages; /**< Whether we've received valid mavlink messages. */
+
+ unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
- unsigned _main_loop_delay; /**< mainloop delay, depends on data rate */
+ MavlinkOrbSubscription *_subscriptions;
+ MavlinkStream *_streams;
- MavlinkOrbSubscription *_subscriptions;
- MavlinkStream *_streams;
+ MavlinkMissionManager *_mission_manager;
orb_advert_t _mission_pub;
- struct mission_s mission;
+ int _mission_result_sub;
MAVLINK_MODE _mode;
- uint8_t _mavlink_wpm_comp_id;
mavlink_channel_t _channel;
struct mavlink_logbuffer _logbuffer;
- unsigned int _total_counter;
-
- pthread_t _receive_thread;
+ unsigned int _total_counter;
- /* Allocate storage space for waypoints */
- mavlink_wpm_storage _wpm_s;
- mavlink_wpm_storage *_wpm;
+ pthread_t _receive_thread;
- bool _verbose;
- bool _forwarding_on;
- bool _passing_on;
- int _uart_fd;
- int _baudrate;
- int _datarate;
+ bool _verbose;
+ bool _forwarding_on;
+ bool _passing_on;
+ bool _ftp_on;
+ int _uart_fd;
+ int _baudrate;
+ int _datarate;
/**
* If the queue index is not at 0, the queue sending
* logic will send parameters from the current index
* to len - 1, the end of the param list.
*/
- unsigned int _mavlink_param_queue_index;
+ unsigned int _mavlink_param_queue_index;
- bool mavlink_link_termination_allowed;
+ bool mavlink_link_termination_allowed;
- char *_subscribe_to_stream;
- float _subscribe_to_stream_rate;
+ char *_subscribe_to_stream;
+ float _subscribe_to_stream_rate;
- bool _flow_control_enabled;
+ bool _flow_control_enabled;
struct mavlink_message_buffer {
int write_ptr;
@@ -277,11 +291,19 @@ private:
int size;
char *data;
};
- mavlink_message_buffer _message_buffer;
- pthread_mutex_t _message_buffer_mutex;
+ mavlink_message_buffer _message_buffer;
- perf_counter_t _loop_perf; /**< loop performance counter */
+ pthread_mutex_t _message_buffer_mutex;
+
+ bool _param_initialized;
+ param_t _param_system_id;
+ param_t _param_component_id;
+ param_t _param_system_type;
+ param_t _param_use_hil_gps;
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _txerr_perf; /**< TX error counter */
/**
* Send one parameter.
@@ -289,7 +311,7 @@ private:
* @param param The parameter id to send.
* @return zero on success, nonzero on failure.
*/
- int mavlink_pm_send_param(param_t param);
+ int mavlink_pm_send_param(param_t param);
/**
* Send one parameter identified by index.
@@ -297,7 +319,7 @@ private:
* @param index The index of the parameter to send.
* @return zero on success, nonzero else.
*/
- int mavlink_pm_send_param_for_index(uint16_t index);
+ int mavlink_pm_send_param_for_index(uint16_t index);
/**
* Send one parameter identified by name.
@@ -305,14 +327,14 @@ private:
* @param name The index of the parameter to send.
* @return zero on success, nonzero else.
*/
- int mavlink_pm_send_param_for_name(const char *name);
+ int mavlink_pm_send_param_for_name(const char *name);
/**
* Send a queue of parameters, one parameter per function call.
*
* @return zero on success, nonzero on failure
*/
- int mavlink_pm_queued_send(void);
+ int mavlink_pm_queued_send(void);
/**
* Start sending the parameter queue.
@@ -322,29 +344,13 @@ private:
* mavlink_pm_queued_send().
* @see mavlink_pm_queued_send()
*/
- void mavlink_pm_start_queued_send();
-
- void mavlink_update_system();
+ void mavlink_pm_start_queued_send();
- void mavlink_waypoint_eventloop(uint64_t now);
- void mavlink_wpm_send_waypoint_reached(uint16_t seq);
- void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq);
- void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq);
- void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count);
- void mavlink_wpm_send_waypoint_current(uint16_t seq);
- void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type);
- void mavlink_wpm_init(mavlink_wpm_storage *state);
- int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
- int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
- void publish_mission();
-
- void mavlink_missionlib_send_message(mavlink_message_t *msg);
- int mavlink_missionlib_send_gcs_string(const char *string);
+ void mavlink_update_system();
int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb);
int configure_stream(const char *stream_name, const float rate);
- void configure_stream_threadsafe(const char *stream_name, const float rate);
int message_buffer_init(int size);
@@ -354,13 +360,11 @@ private:
int message_buffer_is_empty();
- bool message_buffer_write(void *ptr, int size);
-
int message_buffer_get_ptr(void **ptr, bool *is_part);
void message_buffer_mark_read(int n);
- void pass_message(mavlink_message_t *msg);
+ void pass_message(const mavlink_message_t *msg);
static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg);
@@ -368,5 +372,4 @@ private:
* Main mavlink task.
*/
int task_main(int argc, char *argv[]);
-
};
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index d94e7fc7e..7c864f127 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -45,7 +45,6 @@
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/rc_channels.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -74,6 +73,8 @@
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_range_finder.h>
+#include <systemlib/err.h>
+
#include "mavlink_messages.h"
@@ -118,50 +119,90 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
union px4_custom_mode custom_mode;
custom_mode.data = 0;
- if (pos_sp_triplet->nav_state == NAV_STATE_NONE) {
- /* use main state when navigator is not active */
- if (status->main_state == MAIN_STATE_MANUAL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
+ switch (status->nav_state) {
+
+ case NAVIGATION_STATE_MANUAL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
+ break;
+
+ case NAVIGATION_STATE_ACRO:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
+ break;
- } else if (status->main_state == MAIN_STATE_ALTCTL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
+ case NAVIGATION_STATE_ALTCTL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
+ break;
- } else if (status->main_state == MAIN_STATE_POSCTL) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
+ case NAVIGATION_STATE_POSCTL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
+ break;
- } else if (status->main_state == MAIN_STATE_AUTO) {
- *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
+ case NAVIGATION_STATE_AUTO_MISSION:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
+ break;
- } else if (status->main_state == MAIN_STATE_ACRO) {
- *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
- }
+ case NAVIGATION_STATE_AUTO_LOITER:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ break;
- } else {
- /* use navigation state when navigator is active */
- *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ case NAVIGATION_STATE_AUTO_RTL:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
+ break;
+
+ case NAVIGATION_STATE_LAND:
+ /* fallthrough */
+ case NAVIGATION_STATE_DESCEND:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
+ break;
- if (pos_sp_triplet->nav_state == NAV_STATE_READY) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+ case NAVIGATION_STATE_AUTO_RTGS:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
+ custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTGS;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_LOITER) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LOITER;
+ case NAVIGATION_STATE_TERMINATION:
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_MISSION) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_MISSION;
+ case NAVIGATION_STATE_OFFBOARD:
+ *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED
+ | MAV_MODE_FLAG_STABILIZE_ENABLED
+ | MAV_MODE_FLAG_GUIDED_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD;
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_RTL) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL;
+ case NAVIGATION_STATE_MAX:
+ /* this is an unused case, ignore */
+ break;
- } else if (pos_sp_triplet->nav_state == NAV_STATE_LAND) {
- custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_LAND;
- }
}
*mavlink_custom_mode = custom_mode.data;
@@ -193,42 +234,57 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
class MavlinkStreamHeartbeat : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamHeartbeat::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "HEARTBEAT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_HEARTBEAT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamHeartbeat();
}
private:
MavlinkOrbSubscription *status_sub;
- struct vehicle_status_s *status;
-
MavlinkOrbSubscription *pos_sp_triplet_sub;
- struct position_setpoint_triplet_s *pos_sp_triplet;
protected:
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
- status = (struct vehicle_status_s *)status_sub->get_data();
-
pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet));
- pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data();
}
void send(const hrt_abstime t)
{
- (void)status_sub->update(t);
- (void)pos_sp_triplet_sub->update(t);
+ struct vehicle_status_s status;
+ struct position_setpoint_triplet_s pos_sp_triplet;
+
+ /* always send the heartbeat, independent of the update status of the topics */
+ if (!status_sub->update(&status)) {
+ /* if topic update failed fill it with defaults */
+ memset(&status, 0, sizeof(status));
+ }
+
+ if (!pos_sp_triplet_sub->update(&pos_sp_triplet)) {
+ /* if topic update failed fill it with defaults */
+ memset(&pos_sp_triplet, 0, sizeof(pos_sp_triplet));
+ }
uint8_t mavlink_state = 0;
uint8_t mavlink_base_mode = 0;
uint32_t mavlink_custom_mode = 0;
- get_mavlink_mode_state(status, pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
+ get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
mavlink_msg_heartbeat_send(_channel,
mavlink_system.type,
@@ -236,7 +292,6 @@ protected:
mavlink_base_mode,
mavlink_custom_mode,
mavlink_state);
-
}
};
@@ -244,44 +299,55 @@ protected:
class MavlinkStreamSysStatus : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamSysStatus::get_name_static();
+ }
+
+ static const char *get_name_static ()
{
return "SYS_STATUS";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_SYS_STATUS;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamSysStatus();
}
private:
MavlinkOrbSubscription *status_sub;
- struct vehicle_status_s *status;
protected:
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
- status = (struct vehicle_status_s *)status_sub->get_data();
}
void send(const hrt_abstime t)
{
- status_sub->update(t);
- mavlink_msg_sys_status_send(_channel,
- status->onboard_control_sensors_present,
- status->onboard_control_sensors_enabled,
- status->onboard_control_sensors_health,
- status->load * 1000.0f,
- status->battery_voltage * 1000.0f,
- status->battery_current * 100.0f,
- status->battery_remaining * 100.0f,
- status->drop_rate_comm,
- status->errors_comm,
- status->errors_count1,
- status->errors_count2,
- status->errors_count3,
- status->errors_count4);
+ struct vehicle_status_s status;
+
+ if (status_sub->update(&status)) {
+ mavlink_msg_sys_status_send(_channel,
+ status.onboard_control_sensors_present,
+ status.onboard_control_sensors_enabled,
+ status.onboard_control_sensors_health,
+ status.load * 1000.0f,
+ status.battery_voltage * 1000.0f,
+ status.battery_current * 100.0f,
+ status.battery_remaining * 100.0f,
+ status.drop_rate_comm,
+ status.errors_comm,
+ status.errors_count1,
+ status.errors_count2,
+ status.errors_count3,
+ status.errors_count4);
+ }
}
};
@@ -289,23 +355,29 @@ protected:
class MavlinkStreamHighresIMU : public MavlinkStream
{
public:
- MavlinkStreamHighresIMU() : MavlinkStream(), accel_timestamp(0), gyro_timestamp(0), mag_timestamp(0), baro_timestamp(0)
+ const char *get_name() const
{
+ return MavlinkStreamHighresIMU::get_name_static();
}
- const char *get_name()
+ static const char *get_name_static()
{
return "HIGHRES_IMU";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_HIGHRES_IMU;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamHighresIMU();
}
private:
MavlinkOrbSubscription *sensor_sub;
- struct sensor_combined_s *sensor;
+ uint64_t sensor_time;
uint64_t accel_timestamp;
uint64_t gyro_timestamp;
@@ -313,48 +385,57 @@ private:
uint64_t baro_timestamp;
protected:
+ explicit MavlinkStreamHighresIMU() : MavlinkStream(),
+ sensor_time(0),
+ accel_timestamp(0),
+ gyro_timestamp(0),
+ mag_timestamp(0),
+ baro_timestamp(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
sensor_sub = mavlink->add_orb_subscription(ORB_ID(sensor_combined));
- sensor = (struct sensor_combined_s *)sensor_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (sensor_sub->update(t)) {
+ struct sensor_combined_s sensor;
+
+ if (sensor_sub->update(&sensor_time, &sensor)) {
uint16_t fields_updated = 0;
- if (accel_timestamp != sensor->accelerometer_timestamp) {
+ if (accel_timestamp != sensor.accelerometer_timestamp) {
/* mark first three dimensions as changed */
fields_updated |= (1 << 0) | (1 << 1) | (1 << 2);
- accel_timestamp = sensor->accelerometer_timestamp;
+ accel_timestamp = sensor.accelerometer_timestamp;
}
- if (gyro_timestamp != sensor->timestamp) {
+ if (gyro_timestamp != sensor.timestamp) {
/* mark second group dimensions as changed */
fields_updated |= (1 << 3) | (1 << 4) | (1 << 5);
- gyro_timestamp = sensor->timestamp;
+ gyro_timestamp = sensor.timestamp;
}
- if (mag_timestamp != sensor->magnetometer_timestamp) {
+ if (mag_timestamp != sensor.magnetometer_timestamp) {
/* mark third group dimensions as changed */
fields_updated |= (1 << 6) | (1 << 7) | (1 << 8);
- mag_timestamp = sensor->magnetometer_timestamp;
+ mag_timestamp = sensor.magnetometer_timestamp;
}
- if (baro_timestamp != sensor->baro_timestamp) {
+ if (baro_timestamp != sensor.baro_timestamp) {
/* mark last group dimensions as changed */
fields_updated |= (1 << 9) | (1 << 11) | (1 << 12);
- baro_timestamp = sensor->baro_timestamp;
+ baro_timestamp = sensor.baro_timestamp;
}
mavlink_msg_highres_imu_send(_channel,
- sensor->timestamp,
- sensor->accelerometer_m_s2[0], sensor->accelerometer_m_s2[1], sensor->accelerometer_m_s2[2],
- sensor->gyro_rad_s[0], sensor->gyro_rad_s[1], sensor->gyro_rad_s[2],
- sensor->magnetometer_ga[0], sensor->magnetometer_ga[1], sensor->magnetometer_ga[2],
- sensor->baro_pres_mbar, sensor->differential_pressure_pa,
- sensor->baro_alt_meter, sensor->baro_temp_celcius,
+ sensor.timestamp,
+ sensor.accelerometer_m_s2[0], sensor.accelerometer_m_s2[1], sensor.accelerometer_m_s2[2],
+ sensor.gyro_rad_s[0], sensor.gyro_rad_s[1], sensor.gyro_rad_s[2],
+ sensor.magnetometer_ga[0], sensor.magnetometer_ga[1], sensor.magnetometer_ga[2],
+ sensor.baro_pres_mbar, sensor.differential_pressure_pa,
+ sensor.baro_alt_meter, sensor.baro_temp_celcius,
fields_updated);
}
}
@@ -364,34 +445,49 @@ protected:
class MavlinkStreamAttitude : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamAttitude::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "ATTITUDE";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_ATTITUDE;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamAttitude();
}
private:
MavlinkOrbSubscription *att_sub;
- struct vehicle_attitude_s *att;
+ uint64_t att_time;
protected:
+ explicit MavlinkStreamAttitude() : MavlinkStream(),
+ att_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude));
- att = (struct vehicle_attitude_s *)att_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (att_sub->update(t)) {
+ struct vehicle_attitude_s att;
+
+ if (att_sub->update(&att_time, &att)) {
mavlink_msg_attitude_send(_channel,
- att->timestamp / 1000,
- att->roll, att->pitch, att->yaw,
- att->rollspeed, att->pitchspeed, att->yawspeed);
+ att.timestamp / 1000,
+ att.roll, att.pitch, att.yaw,
+ att.rollspeed, att.pitchspeed, att.yawspeed);
}
}
};
@@ -400,39 +496,54 @@ protected:
class MavlinkStreamAttitudeQuaternion : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamAttitudeQuaternion::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "ATTITUDE_QUATERNION";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamAttitudeQuaternion();
}
private:
MavlinkOrbSubscription *att_sub;
- struct vehicle_attitude_s *att;
+ uint64_t att_time;
protected:
+ explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(),
+ att_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude));
- att = (struct vehicle_attitude_s *)att_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (att_sub->update(t)) {
+ struct vehicle_attitude_s att;
+
+ if (att_sub->update(&att_time, &att)) {
mavlink_msg_attitude_quaternion_send(_channel,
- att->timestamp / 1000,
- att->q[0],
- att->q[1],
- att->q[2],
- att->q[3],
- att->rollspeed,
- att->pitchspeed,
- att->yawspeed);
+ att.timestamp / 1000,
+ att.q[0],
+ att.q[1],
+ att.q[2],
+ att.q[3],
+ att.rollspeed,
+ att.pitchspeed,
+ att.yawspeed);
}
}
};
@@ -441,71 +552,87 @@ protected:
class MavlinkStreamVFRHUD : public MavlinkStream
{
public:
- const char *get_name()
+
+ const char *get_name() const
+ {
+ return MavlinkStreamVFRHUD::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "VFR_HUD";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_VFR_HUD;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamVFRHUD();
}
private:
MavlinkOrbSubscription *att_sub;
- struct vehicle_attitude_s *att;
+ uint64_t att_time;
MavlinkOrbSubscription *pos_sub;
- struct vehicle_global_position_s *pos;
+ uint64_t pos_time;
MavlinkOrbSubscription *armed_sub;
- struct actuator_armed_s *armed;
+ uint64_t armed_time;
MavlinkOrbSubscription *act_sub;
- struct actuator_controls_s *act;
+ uint64_t act_time;
MavlinkOrbSubscription *airspeed_sub;
- struct airspeed_s *airspeed;
+ uint64_t airspeed_time;
protected:
+ explicit MavlinkStreamVFRHUD() : MavlinkStream(),
+ att_time(0),
+ pos_time(0),
+ armed_time(0),
+ act_time(0),
+ airspeed_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude));
- att = (struct vehicle_attitude_s *)att_sub->get_data();
-
pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position));
- pos = (struct vehicle_global_position_s *)pos_sub->get_data();
-
armed_sub = mavlink->add_orb_subscription(ORB_ID(actuator_armed));
- armed = (struct actuator_armed_s *)armed_sub->get_data();
-
act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_controls_0));
- act = (struct actuator_controls_s *)act_sub->get_data();
-
airspeed_sub = mavlink->add_orb_subscription(ORB_ID(airspeed));
- airspeed = (struct airspeed_s *)airspeed_sub->get_data();
}
void send(const hrt_abstime t)
{
- bool updated = att_sub->update(t);
- updated |= pos_sub->update(t);
- updated |= armed_sub->update(t);
- updated |= act_sub->update(t);
- updated |= airspeed_sub->update(t);
+ struct vehicle_attitude_s att;
+ struct vehicle_global_position_s pos;
+ struct actuator_armed_s armed;
+ struct actuator_controls_s act;
+ struct airspeed_s airspeed;
+
+ bool updated = att_sub->update(&att_time, &att);
+ updated |= pos_sub->update(&pos_time, &pos);
+ updated |= armed_sub->update(&armed_time, &armed);
+ updated |= act_sub->update(&act_time, &act);
+ updated |= airspeed_sub->update(&airspeed_time, &airspeed);
if (updated) {
- float groundspeed = sqrtf(pos->vel_n * pos->vel_n + pos->vel_e * pos->vel_e);
- uint16_t heading = _wrap_2pi(att->yaw) * M_RAD_TO_DEG_F;
- float throttle = armed->armed ? act->control[3] * 100.0f : 0.0f;
+ float groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e);
+ uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
+ float throttle = armed.armed ? act.control[3] * 100.0f : 0.0f;
mavlink_msg_vfr_hud_send(_channel,
- airspeed->true_airspeed_m_s,
+ airspeed.true_airspeed_m_s,
groundspeed,
heading,
throttle,
- pos->alt,
- -pos->vel_d);
+ pos.alt,
+ -pos.vel_d);
}
}
};
@@ -514,41 +641,56 @@ protected:
class MavlinkStreamGPSRawInt : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamGPSRawInt::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "GPS_RAW_INT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_GPS_RAW_INT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamGPSRawInt();
}
private:
MavlinkOrbSubscription *gps_sub;
- struct vehicle_gps_position_s *gps;
+ uint64_t gps_time;
protected:
+ explicit MavlinkStreamGPSRawInt() : MavlinkStream(),
+ gps_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position));
- gps = (struct vehicle_gps_position_s *)gps_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (gps_sub->update(t)) {
+ struct vehicle_gps_position_s gps;
+
+ if (gps_sub->update(&gps_time, &gps)) {
mavlink_msg_gps_raw_int_send(_channel,
- gps->timestamp_position,
- gps->fix_type,
- gps->lat,
- gps->lon,
- gps->alt,
- cm_uint16_from_m_float(gps->eph_m),
- cm_uint16_from_m_float(gps->epv_m),
- gps->vel_m_s * 100.0f,
- _wrap_2pi(gps->cog_rad) * M_RAD_TO_DEG_F * 1e2f,
- gps->satellites_visible);
+ gps.timestamp_position,
+ gps.fix_type,
+ gps.lat,
+ gps.lon,
+ gps.alt,
+ cm_uint16_from_m_float(gps.eph),
+ cm_uint16_from_m_float(gps.epv),
+ gps.vel_m_s * 100.0f,
+ _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
+ gps.satellites_used);
}
}
};
@@ -557,49 +699,64 @@ protected:
class MavlinkStreamGlobalPositionInt : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamGlobalPositionInt::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "GLOBAL_POSITION_INT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamGlobalPositionInt();
}
private:
MavlinkOrbSubscription *pos_sub;
- struct vehicle_global_position_s *pos;
+ uint64_t pos_time;
MavlinkOrbSubscription *home_sub;
- struct home_position_s *home;
+ uint64_t home_time;
protected:
+ explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(),
+ pos_time(0),
+ home_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position));
- pos = (struct vehicle_global_position_s *)pos_sub->get_data();
-
home_sub = mavlink->add_orb_subscription(ORB_ID(home_position));
- home = (struct home_position_s *)home_sub->get_data();
}
void send(const hrt_abstime t)
{
- bool updated = pos_sub->update(t);
- updated |= home_sub->update(t);
+ struct vehicle_global_position_s pos;
+ struct home_position_s home;
+
+ bool updated = pos_sub->update(&pos_time, &pos);
+ updated |= home_sub->update(&home_time, &home);
if (updated) {
mavlink_msg_global_position_int_send(_channel,
- pos->timestamp / 1000,
- pos->lat * 1e7,
- pos->lon * 1e7,
- pos->alt * 1000.0f,
- (pos->alt - home->alt) * 1000.0f,
- pos->vel_n * 100.0f,
- pos->vel_e * 100.0f,
- pos->vel_d * 100.0f,
- _wrap_2pi(pos->yaw) * M_RAD_TO_DEG_F * 100.0f);
+ pos.timestamp / 1000,
+ pos.lat * 1e7,
+ pos.lon * 1e7,
+ pos.alt * 1000.0f,
+ (pos.alt - home.alt) * 1000.0f,
+ pos.vel_n * 100.0f,
+ pos.vel_e * 100.0f,
+ pos.vel_d * 100.0f,
+ _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f);
}
}
};
@@ -608,38 +765,53 @@ protected:
class MavlinkStreamLocalPositionNED : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamLocalPositionNED::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "LOCAL_POSITION_NED";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_LOCAL_POSITION_NED;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamLocalPositionNED();
}
private:
MavlinkOrbSubscription *pos_sub;
- struct vehicle_local_position_s *pos;
+ uint64_t pos_time;
protected:
+ explicit MavlinkStreamLocalPositionNED() : MavlinkStream(),
+ pos_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position));
- pos = (struct vehicle_local_position_s *)pos_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (pos_sub->update(t)) {
+ struct vehicle_local_position_s pos;
+
+ if (pos_sub->update(&pos_time, &pos)) {
mavlink_msg_local_position_ned_send(_channel,
- pos->timestamp / 1000,
- pos->x,
- pos->y,
- pos->z,
- pos->vx,
- pos->vy,
- pos->vz);
+ pos.timestamp / 1000,
+ pos.x,
+ pos.y,
+ pos.z,
+ pos.vx,
+ pos.vy,
+ pos.vz);
}
}
};
@@ -649,38 +821,53 @@ protected:
class MavlinkStreamViconPositionEstimate : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamViconPositionEstimate::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "VICON_POSITION_ESTIMATE";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamViconPositionEstimate();
}
private:
MavlinkOrbSubscription *pos_sub;
- struct vehicle_vicon_position_s *pos;
+ uint64_t pos_time;
protected:
+ explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(),
+ pos_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position));
- pos = (struct vehicle_vicon_position_s *)pos_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (pos_sub->update(t)) {
+ struct vehicle_vicon_position_s pos;
+
+ if (pos_sub->update(&pos_time, &pos)) {
mavlink_msg_vicon_position_estimate_send(_channel,
- pos->timestamp / 1000,
- pos->x,
- pos->y,
- pos->z,
- pos->roll,
- pos->pitch,
- pos->yaw);
+ pos.timestamp / 1000,
+ pos.x,
+ pos.y,
+ pos.z,
+ pos.roll,
+ pos.pitch,
+ pos.yaw);
}
}
};
@@ -689,70 +876,97 @@ protected:
class MavlinkStreamGPSGlobalOrigin : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamGPSGlobalOrigin::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "GPS_GLOBAL_ORIGIN";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamGPSGlobalOrigin();
}
private:
MavlinkOrbSubscription *home_sub;
- struct home_position_s *home;
protected:
void subscribe(Mavlink *mavlink)
{
home_sub = mavlink->add_orb_subscription(ORB_ID(home_position));
- home = (struct home_position_s *)home_sub->get_data();
}
void send(const hrt_abstime t)
{
-
/* we're sending the GPS home periodically to ensure the
* the GCS does pick it up at one point */
if (home_sub->is_published()) {
- home_sub->update(t);
+ struct home_position_s home;
- mavlink_msg_gps_global_origin_send(_channel,
- (int32_t)(home->lat * 1e7),
- (int32_t)(home->lon * 1e7),
- (int32_t)(home->alt) * 1000.0f);
+ if (home_sub->update(&home)) {
+ mavlink_msg_gps_global_origin_send(_channel,
+ (int32_t)(home.lat * 1e7),
+ (int32_t)(home.lon * 1e7),
+ (int32_t)(home.alt) * 1000.0f);
+ }
}
}
};
-
+template <int N>
class MavlinkStreamServoOutputRaw : public MavlinkStream
{
public:
- MavlinkStreamServoOutputRaw(unsigned int n) : MavlinkStream(), _n(n)
+ const char *get_name() const
{
- sprintf(_name, "SERVO_OUTPUT_RAW_%d", _n);
+ return MavlinkStreamServoOutputRaw<N>::get_name_static();
}
- const char *get_name()
+ uint8_t get_id()
{
- return _name;
+ return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
}
- MavlinkStream *new_instance()
+ static const char *get_name_static()
{
- return new MavlinkStreamServoOutputRaw(_n);
+ switch (N) {
+ case 0:
+ return "SERVO_OUTPUT_RAW_0";
+
+ case 1:
+ return "SERVO_OUTPUT_RAW_1";
+
+ case 2:
+ return "SERVO_OUTPUT_RAW_2";
+
+ case 3:
+ return "SERVO_OUTPUT_RAW_3";
+ }
+ }
+
+ static MavlinkStream *new_instance()
+ {
+ return new MavlinkStreamServoOutputRaw<N>();
}
private:
MavlinkOrbSubscription *act_sub;
- struct actuator_outputs_s *act;
-
- char _name[20];
- unsigned int _n;
+ uint64_t act_time;
protected:
+ explicit MavlinkStreamServoOutputRaw() : MavlinkStream(),
+ act_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
orb_id_t act_topics[] = {
@@ -762,24 +976,25 @@ protected:
ORB_ID(actuator_outputs_3)
};
- act_sub = mavlink->add_orb_subscription(act_topics[_n]);
- act = (struct actuator_outputs_s *)act_sub->get_data();
+ act_sub = mavlink->add_orb_subscription(act_topics[N]);
}
void send(const hrt_abstime t)
{
- if (act_sub->update(t)) {
+ struct actuator_outputs_s act;
+
+ if (act_sub->update(&act_time, &act)) {
mavlink_msg_servo_output_raw_send(_channel,
- act->timestamp / 1000,
- _n,
- act->output[0],
- act->output[1],
- act->output[2],
- act->output[3],
- act->output[4],
- act->output[5],
- act->output[6],
- act->output[7]);
+ act.timestamp / 1000,
+ N,
+ act.output[0],
+ act.output[1],
+ act.output[2],
+ act.output[3],
+ act.output[4],
+ act.output[5],
+ act.output[6],
+ act.output[7]);
}
}
};
@@ -788,56 +1003,77 @@ protected:
class MavlinkStreamHILControls : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamHILControls::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "HIL_CONTROLS";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_HIL_CONTROLS;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamHILControls();
}
private:
MavlinkOrbSubscription *status_sub;
- struct vehicle_status_s *status;
+ uint64_t status_time;
MavlinkOrbSubscription *pos_sp_triplet_sub;
- struct position_setpoint_triplet_s *pos_sp_triplet;
+ uint64_t pos_sp_triplet_time;
MavlinkOrbSubscription *act_sub;
- struct actuator_outputs_s *act;
+ uint64_t act_time;
protected:
+ explicit MavlinkStreamHILControls() : MavlinkStream(),
+ status_time(0),
+ pos_sp_triplet_time(0),
+ act_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
- status = (struct vehicle_status_s *)status_sub->get_data();
-
pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet));
- pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data();
-
act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0));
- act = (struct actuator_outputs_s *)act_sub->get_data();
}
void send(const hrt_abstime t)
{
- bool updated = act_sub->update(t);
- (void)pos_sp_triplet_sub->update(t);
- (void)status_sub->update(t);
+ struct vehicle_status_s status;
+ struct position_setpoint_triplet_s pos_sp_triplet;
+ struct actuator_outputs_s act;
- if (updated && (status->arming_state == ARMING_STATE_ARMED)) {
+ bool updated = act_sub->update(&act_time, &act);
+ updated |= pos_sp_triplet_sub->update(&pos_sp_triplet_time, &pos_sp_triplet);
+ updated |= status_sub->update(&status_time, &status);
+
+ if (updated && (status.arming_state == ARMING_STATE_ARMED)) {
/* translate the current syste state to mavlink state and mode */
uint8_t mavlink_state;
uint8_t mavlink_base_mode;
uint32_t mavlink_custom_mode;
- get_mavlink_mode_state(status, pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
+ get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode);
+
+ float out[8];
+ const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
+
+ /* scale outputs depending on system type */
if (mavlink_system.type == MAV_TYPE_QUADROTOR ||
mavlink_system.type == MAV_TYPE_HEXAROTOR ||
mavlink_system.type == MAV_TYPE_OCTOROTOR) {
- /* set number of valid outputs depending on vehicle type */
+ /* multirotors: set number of rotor outputs depending on type */
+
unsigned n;
switch (mavlink_system.type) {
@@ -854,59 +1090,44 @@ protected:
break;
}
- /* scale / assign outputs depending on system type */
- float out[8];
-
for (unsigned i = 0; i < 8; i++) {
- if (i < n) {
- if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
- /* scale fake PWM out 900..2100 us to 0..1 for normal multirotors */
- out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+ if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) {
+ if (i < n) {
+ /* scale PWM out 900..2100 us to 0..1 for rotors */
+ out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
} else {
- /* send 0 when disarmed */
- out[i] = 0.0f;
+ /* scale PWM out 900..2100 us to -1..1 for other channels */
+ out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
}
} else {
- out[i] = -1.0f;
+ /* send 0 when disarmed */
+ out[i] = 0.0f;
}
}
- mavlink_msg_hil_controls_send(_channel,
- hrt_absolute_time(),
- out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
- mavlink_base_mode,
- 0);
} else {
-
- /* fixed wing: scale all channels except throttle -1 .. 1
- * because we know that we set the mixers up this way
- */
-
- float out[8];
-
- const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2;
+ /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */
for (unsigned i = 0; i < 8; i++) {
if (i != 3) {
- /* scale fake PWM out 900..2100 us to -1..+1 for normal channels */
- out[i] = (act->output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
+ /* scale PWM out 900..2100 us to -1..1 for normal channels */
+ out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2);
} else {
-
- /* scale fake PWM out 900..2100 us to 0..1 for throttle */
- out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
+ /* scale PWM out 900..2100 us to 0..1 for throttle */
+ out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN);
}
}
-
- mavlink_msg_hil_controls_send(_channel,
- hrt_absolute_time(),
- out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
- mavlink_base_mode,
- 0);
}
+
+ mavlink_msg_hil_controls_send(_channel,
+ hrt_absolute_time(),
+ out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7],
+ mavlink_base_mode,
+ 0);
}
}
};
@@ -915,37 +1136,47 @@ protected:
class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamGlobalPositionSetpointInt::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "GLOBAL_POSITION_SETPOINT_INT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamGlobalPositionSetpointInt();
}
private:
MavlinkOrbSubscription *pos_sp_triplet_sub;
- struct position_setpoint_triplet_s *pos_sp_triplet;
protected:
void subscribe(Mavlink *mavlink)
{
pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet));
- pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data();
}
void send(const hrt_abstime t)
{
- /* always send this message, even if it has not been updated */
- pos_sp_triplet_sub->update(t);
- mavlink_msg_global_position_setpoint_int_send(_channel,
- MAV_FRAME_GLOBAL,
- (int32_t)(pos_sp_triplet->current.lat * 1e7),
- (int32_t)(pos_sp_triplet->current.lon * 1e7),
- (int32_t)(pos_sp_triplet->current.alt * 1000),
- (int16_t)(pos_sp_triplet->current.yaw * M_RAD_TO_DEG_F * 100.0f));
+ struct position_setpoint_triplet_s pos_sp_triplet;
+
+ if (pos_sp_triplet_sub->update(&pos_sp_triplet)) {
+ mavlink_msg_global_position_setpoint_int_send(_channel,
+ MAV_FRAME_GLOBAL,
+ (int32_t)(pos_sp_triplet.current.lat * 1e7),
+ (int32_t)(pos_sp_triplet.current.lon * 1e7),
+ (int32_t)(pos_sp_triplet.current.alt * 1000),
+ (int16_t)(pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f));
+ }
}
};
@@ -953,36 +1184,51 @@ protected:
class MavlinkStreamLocalPositionSetpoint : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamLocalPositionSetpoint::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "LOCAL_POSITION_SETPOINT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamLocalPositionSetpoint();
}
private:
MavlinkOrbSubscription *pos_sp_sub;
- struct vehicle_local_position_setpoint_s *pos_sp;
+ uint64_t pos_sp_time;
protected:
+ explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(),
+ pos_sp_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint));
- pos_sp = (struct vehicle_local_position_setpoint_s *)pos_sp_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (pos_sp_sub->update(t)) {
+ struct vehicle_local_position_setpoint_s pos_sp;
+
+ if (pos_sp_sub->update(&pos_sp_time, &pos_sp)) {
mavlink_msg_local_position_setpoint_send(_channel,
MAV_FRAME_LOCAL_NED,
- pos_sp->x,
- pos_sp->y,
- pos_sp->z,
- pos_sp->yaw);
+ pos_sp.x,
+ pos_sp.y,
+ pos_sp.z,
+ pos_sp.yaw);
}
}
};
@@ -991,36 +1237,51 @@ protected:
class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "ROLL_PITCH_YAW_THRUST_SETPOINT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamRollPitchYawThrustSetpoint();
}
private:
MavlinkOrbSubscription *att_sp_sub;
- struct vehicle_attitude_setpoint_s *att_sp;
+ uint64_t att_sp_time;
protected:
+ explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(),
+ att_sp_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint));
- att_sp = (struct vehicle_attitude_setpoint_s *)att_sp_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (att_sp_sub->update(t)) {
+ struct vehicle_attitude_setpoint_s att_sp;
+
+ if (att_sp_sub->update(&att_sp_time, &att_sp)) {
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(_channel,
- att_sp->timestamp / 1000,
- att_sp->roll_body,
- att_sp->pitch_body,
- att_sp->yaw_body,
- att_sp->thrust);
+ att_sp.timestamp / 1000,
+ att_sp.roll_body,
+ att_sp.pitch_body,
+ att_sp.yaw_body,
+ att_sp.thrust);
}
}
};
@@ -1029,36 +1290,51 @@ protected:
class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamRollPitchYawRatesThrustSetpoint();
}
private:
MavlinkOrbSubscription *att_rates_sp_sub;
- struct vehicle_rates_setpoint_s *att_rates_sp;
+ uint64_t att_rates_sp_time;
protected:
+ explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(),
+ att_rates_sp_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint));
- att_rates_sp = (struct vehicle_rates_setpoint_s *)att_rates_sp_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (att_rates_sp_sub->update(t)) {
+ struct vehicle_rates_setpoint_s att_rates_sp;
+
+ if (att_rates_sp_sub->update(&att_rates_sp_time, &att_rates_sp)) {
mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(_channel,
- att_rates_sp->timestamp / 1000,
- att_rates_sp->roll,
- att_rates_sp->pitch,
- att_rates_sp->yaw,
- att_rates_sp->thrust);
+ att_rates_sp.timestamp / 1000,
+ att_rates_sp.roll,
+ att_rates_sp.pitch,
+ att_rates_sp.yaw,
+ att_rates_sp.thrust);
}
}
};
@@ -1067,47 +1343,87 @@ protected:
class MavlinkStreamRCChannelsRaw : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamRCChannelsRaw::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "RC_CHANNELS_RAW";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_RC_CHANNELS_RAW;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamRCChannelsRaw();
}
private:
MavlinkOrbSubscription *rc_sub;
- struct rc_input_values *rc;
+ uint64_t rc_time;
protected:
+ explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(),
+ rc_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc));
- rc = (struct rc_input_values *)rc_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (rc_sub->update(t)) {
+ struct rc_input_values rc;
+
+ if (rc_sub->update(&rc_time, &rc)) {
const unsigned port_width = 8;
- for (unsigned i = 0; (i * port_width) < rc->channel_count; i++) {
+ // Deprecated message (but still needed for compatibility!)
+ for (unsigned i = 0; (i * port_width) < rc.channel_count; i++) {
/* Channels are sent in MAVLink main loop at a fixed interval */
mavlink_msg_rc_channels_raw_send(_channel,
- rc->timestamp_publication / 1000,
+ rc.timestamp_publication / 1000,
i,
- (rc->channel_count > (i * port_width) + 0) ? rc->values[(i * port_width) + 0] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 1) ? rc->values[(i * port_width) + 1] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 2) ? rc->values[(i * port_width) + 2] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 3) ? rc->values[(i * port_width) + 3] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 4) ? rc->values[(i * port_width) + 4] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 5) ? rc->values[(i * port_width) + 5] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 6) ? rc->values[(i * port_width) + 6] : UINT16_MAX,
- (rc->channel_count > (i * port_width) + 7) ? rc->values[(i * port_width) + 7] : UINT16_MAX,
- rc->rssi);
+ (rc.channel_count > (i * port_width) + 0) ? rc.values[(i * port_width) + 0] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX,
+ (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX,
+ rc.rssi);
}
+
+ // New message
+ mavlink_msg_rc_channels_send(_channel,
+ rc.timestamp_publication / 1000,
+ rc.channel_count,
+ ((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX),
+ ((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX),
+ ((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX),
+ ((rc.channel_count > 3) ? rc.values[3] : UINT16_MAX),
+ ((rc.channel_count > 4) ? rc.values[4] : UINT16_MAX),
+ ((rc.channel_count > 5) ? rc.values[5] : UINT16_MAX),
+ ((rc.channel_count > 6) ? rc.values[6] : UINT16_MAX),
+ ((rc.channel_count > 7) ? rc.values[7] : UINT16_MAX),
+ ((rc.channel_count > 8) ? rc.values[8] : UINT16_MAX),
+ ((rc.channel_count > 9) ? rc.values[9] : UINT16_MAX),
+ ((rc.channel_count > 10) ? rc.values[10] : UINT16_MAX),
+ ((rc.channel_count > 11) ? rc.values[11] : UINT16_MAX),
+ ((rc.channel_count > 12) ? rc.values[12] : UINT16_MAX),
+ ((rc.channel_count > 13) ? rc.values[13] : UINT16_MAX),
+ ((rc.channel_count > 14) ? rc.values[14] : UINT16_MAX),
+ ((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX),
+ ((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX),
+ ((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX),
+ rc.rssi);
}
}
};
@@ -1116,36 +1432,51 @@ protected:
class MavlinkStreamManualControl : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamManualControl::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "MANUAL_CONTROL";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_MANUAL_CONTROL;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamManualControl();
}
private:
MavlinkOrbSubscription *manual_sub;
- struct manual_control_setpoint_s *manual;
+ uint64_t manual_time;
protected:
+ explicit MavlinkStreamManualControl() : MavlinkStream(),
+ manual_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint));
- manual = (struct manual_control_setpoint_s *)manual_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (manual_sub->update(t)) {
+ struct manual_control_setpoint_s manual;
+
+ if (manual_sub->update(&manual_time, &manual)) {
mavlink_msg_manual_control_send(_channel,
mavlink_system.sysid,
- manual->x * 1000,
- manual->y * 1000,
- manual->z * 1000,
- manual->r * 1000,
+ manual.x * 1000,
+ manual.y * 1000,
+ manual.z * 1000,
+ manual.r * 1000,
0);
}
}
@@ -1155,37 +1486,52 @@ protected:
class MavlinkStreamOpticalFlow : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamOpticalFlow::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "OPTICAL_FLOW";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_OPTICAL_FLOW;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamOpticalFlow();
}
private:
MavlinkOrbSubscription *flow_sub;
- struct optical_flow_s *flow;
+ uint64_t flow_time;
protected:
+ explicit MavlinkStreamOpticalFlow() : MavlinkStream(),
+ flow_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow));
- flow = (struct optical_flow_s *)flow_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (flow_sub->update(t)) {
+ struct optical_flow_s flow;
+
+ if (flow_sub->update(&flow_time, &flow)) {
mavlink_msg_optical_flow_send(_channel,
- flow->timestamp,
- flow->sensor_id,
- flow->flow_raw_x, flow->flow_raw_y,
- flow->flow_comp_x_m, flow->flow_comp_y_m,
- flow->quality,
- flow->ground_distance_m);
+ flow.timestamp,
+ flow.sensor_id,
+ flow.flow_raw_x, flow.flow_raw_y,
+ flow.flow_comp_x_m, flow.flow_comp_y_m,
+ flow.quality,
+ flow.ground_distance_m);
}
}
};
@@ -1193,47 +1539,62 @@ protected:
class MavlinkStreamAttitudeControls : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamAttitudeControls::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "ATTITUDE_CONTROLS";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return 0;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamAttitudeControls();
}
private:
MavlinkOrbSubscription *att_ctrl_sub;
- struct actuator_controls_s *att_ctrl;
+ uint64_t att_ctrl_time;
protected:
+ explicit MavlinkStreamAttitudeControls() : MavlinkStream(),
+ att_ctrl_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- att_ctrl = (struct actuator_controls_s *)att_ctrl_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (att_ctrl_sub->update(t)) {
+ struct actuator_controls_s att_ctrl;
+
+ if (att_ctrl_sub->update(&att_ctrl_time, &att_ctrl)) {
/* send, add spaces so that string buffer is at least 10 chars long */
mavlink_msg_named_value_float_send(_channel,
- att_ctrl->timestamp / 1000,
+ att_ctrl.timestamp / 1000,
"rll ctrl ",
- att_ctrl->control[0]);
+ att_ctrl.control[0]);
mavlink_msg_named_value_float_send(_channel,
- att_ctrl->timestamp / 1000,
+ att_ctrl.timestamp / 1000,
"ptch ctrl ",
- att_ctrl->control[1]);
+ att_ctrl.control[1]);
mavlink_msg_named_value_float_send(_channel,
- att_ctrl->timestamp / 1000,
+ att_ctrl.timestamp / 1000,
"yaw ctrl ",
- att_ctrl->control[2]);
+ att_ctrl.control[2]);
mavlink_msg_named_value_float_send(_channel,
- att_ctrl->timestamp / 1000,
+ att_ctrl.timestamp / 1000,
"thr ctrl ",
- att_ctrl->control[3]);
+ att_ctrl.control[3]);
}
}
};
@@ -1241,37 +1602,52 @@ protected:
class MavlinkStreamNamedValueFloat : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamNamedValueFloat::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "NAMED_VALUE_FLOAT";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamNamedValueFloat();
}
private:
MavlinkOrbSubscription *debug_sub;
- struct debug_key_value_s *debug;
+ uint64_t debug_time;
protected:
+ explicit MavlinkStreamNamedValueFloat() : MavlinkStream(),
+ debug_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value));
- debug = (struct debug_key_value_s *)debug_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (debug_sub->update(t)) {
+ struct debug_key_value_s debug;
+
+ if (debug_sub->update(&debug_time, &debug)) {
/* enforce null termination */
- debug->key[sizeof(debug->key) - 1] = '\0';
+ debug.key[sizeof(debug.key) - 1] = '\0';
mavlink_msg_named_value_float_send(_channel,
- debug->timestamp_ms,
- debug->key,
- debug->value);
+ debug.timestamp_ms,
+ debug.key,
+ debug.value);
}
}
};
@@ -1279,33 +1655,42 @@ protected:
class MavlinkStreamCameraCapture : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamCameraCapture::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "CAMERA_CAPTURE";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return 0;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamCameraCapture();
}
private:
MavlinkOrbSubscription *status_sub;
- struct vehicle_status_s *status;
protected:
void subscribe(Mavlink *mavlink)
{
status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status));
- status = (struct vehicle_status_s *)status_sub->get_data();
}
void send(const hrt_abstime t)
{
- (void)status_sub->update(t);
+ struct vehicle_status_s status;
+ (void)status_sub->update(&status);
- if (status->arming_state == ARMING_STATE_ARMED
- || status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ if (status.arming_state == ARMING_STATE_ARMED
+ || status.arming_state == ARMING_STATE_ARMED_ERROR) {
/* send camera capture on */
mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0);
@@ -1320,34 +1705,49 @@ protected:
class MavlinkStreamDistanceSensor : public MavlinkStream
{
public:
- const char *get_name()
+ const char *get_name() const
+ {
+ return MavlinkStreamDistanceSensor::get_name_static();
+ }
+
+ static const char *get_name_static()
{
return "DISTANCE_SENSOR";
}
- MavlinkStream *new_instance()
+ uint8_t get_id()
+ {
+ return MAVLINK_MSG_ID_DISTANCE_SENSOR;
+ }
+
+ static MavlinkStream *new_instance()
{
return new MavlinkStreamDistanceSensor();
}
private:
MavlinkOrbSubscription *range_sub;
- struct range_finder_report *range;
+ uint64_t range_time;
protected:
+ explicit MavlinkStreamDistanceSensor() : MavlinkStream(),
+ range_time(0)
+ {}
+
void subscribe(Mavlink *mavlink)
{
range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder));
- range = (struct range_finder_report *)range_sub->get_data();
}
void send(const hrt_abstime t)
{
- if (range_sub->update(t)) {
+ struct range_finder_report range;
+
+ if (range_sub->update(&range_time, &range)) {
uint8_t type;
- switch (range->type) {
+ switch (range.type) {
case RANGE_FINDER_TYPE_LASER:
type = MAV_DISTANCE_SENSOR_LASER;
break;
@@ -1357,39 +1757,40 @@ protected:
uint8_t orientation = 0;
uint8_t covariance = 20;
- mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation,
- range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance);
+ mavlink_msg_distance_sensor_send(_channel, range.timestamp / 1000, type, id, orientation,
+ range.minimum_distance*100, range.maximum_distance*100, range.distance*100, covariance);
}
}
};
-MavlinkStream *streams_list[] = {
- new MavlinkStreamHeartbeat(),
- new MavlinkStreamSysStatus(),
- new MavlinkStreamHighresIMU(),
- new MavlinkStreamAttitude(),
- new MavlinkStreamAttitudeQuaternion(),
- new MavlinkStreamVFRHUD(),
- new MavlinkStreamGPSRawInt(),
- new MavlinkStreamGlobalPositionInt(),
- new MavlinkStreamLocalPositionNED(),
- new MavlinkStreamGPSGlobalOrigin(),
- new MavlinkStreamServoOutputRaw(0),
- new MavlinkStreamServoOutputRaw(1),
- new MavlinkStreamServoOutputRaw(2),
- new MavlinkStreamServoOutputRaw(3),
- new MavlinkStreamHILControls(),
- new MavlinkStreamGlobalPositionSetpointInt(),
- new MavlinkStreamLocalPositionSetpoint(),
- new MavlinkStreamRollPitchYawThrustSetpoint(),
- new MavlinkStreamRollPitchYawRatesThrustSetpoint(),
- new MavlinkStreamRCChannelsRaw(),
- new MavlinkStreamManualControl(),
- new MavlinkStreamOpticalFlow(),
- new MavlinkStreamAttitudeControls(),
- new MavlinkStreamNamedValueFloat(),
- new MavlinkStreamCameraCapture(),
- new MavlinkStreamDistanceSensor(),
- new MavlinkStreamViconPositionEstimate(),
+
+StreamListItem *streams_list[] = {
+ new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static),
+ new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static),
+ new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static),
+ new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static),
+ new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static),
+ new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static),
+ new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static),
+ new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static),
+ new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static),
+ new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static),
+ new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static),
+ new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static),
+ new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static),
+ new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static),
+ new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static),
+ new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static),
+ new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static),
+ new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static),
+ new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static),
+ new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
+ new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
+ new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
+ new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
+ new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static),
+ new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static),
+ new StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static),
+ new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static),
nullptr
};
diff --git a/src/modules/mavlink/mavlink_messages.h b/src/modules/mavlink/mavlink_messages.h
index b8823263a..ee64d0e42 100644
--- a/src/modules/mavlink/mavlink_messages.h
+++ b/src/modules/mavlink/mavlink_messages.h
@@ -43,6 +43,19 @@
#include "mavlink_stream.h"
-extern MavlinkStream *streams_list[];
+class StreamListItem {
+
+public:
+ MavlinkStream* (*new_instance)();
+ const char* (*get_name)();
+
+ StreamListItem(MavlinkStream* (*inst)(), const char* (*name)()) :
+ new_instance(inst),
+ get_name(name) {};
+
+ ~StreamListItem() {};
+};
+
+extern StreamListItem *streams_list[];
#endif /* MAVLINK_MESSAGES_H_ */
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
new file mode 100644
index 000000000..068774c47
--- /dev/null
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -0,0 +1,828 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mavlink_mission.cpp
+ * MAVLink mission manager implementation.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include "mavlink_mission.h"
+#include "mavlink_main.h"
+
+#include <math.h>
+#include <lib/geo/geo.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include <dataman/dataman.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
+/* oddly, ERROR is not defined for c++ */
+#ifdef ERROR
+# undef ERROR
+#endif
+static const int ERROR = -1;
+
+
+MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
+ _mavlink(mavlink),
+ _state(MAVLINK_WPM_STATE_IDLE),
+ _time_last_recv(0),
+ _time_last_sent(0),
+ _action_timeout(MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT),
+ _retry_timeout(MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT),
+ _max_count(DM_KEY_WAYPOINTS_OFFBOARD_0_MAX),
+ _dataman_id(0),
+ _count(0),
+ _current_seq(0),
+ _transfer_dataman_id(0),
+ _transfer_count(0),
+ _transfer_seq(0),
+ _transfer_current_seq(0),
+ _transfer_partner_sysid(0),
+ _transfer_partner_compid(0),
+ _offboard_mission_sub(-1),
+ _mission_result_sub(-1),
+ _offboard_mission_pub(-1),
+ _slow_rate_limiter(2000000.0f / mavlink->get_rate_mult()),
+ _verbose(false),
+ _channel(mavlink->get_channel()),
+ _comp_id(MAV_COMP_ID_MISSIONPLANNER)
+{
+ _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
+ _mission_result_sub = orb_subscribe(ORB_ID(mission_result));
+
+ init_offboard_mission();
+}
+
+MavlinkMissionManager::~MavlinkMissionManager()
+{
+ close(_offboard_mission_pub);
+ close(_mission_result_sub);
+}
+
+void
+MavlinkMissionManager::init_offboard_mission()
+{
+ mission_s mission_state;
+ if (dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s)) == sizeof(mission_s)) {
+ _dataman_id = mission_state.dataman_id;
+ _count = mission_state.count;
+ _current_seq = mission_state.current_seq;
+
+ warnx("offboard mission init: dataman_id=%d, count=%u, current_seq=%d", _dataman_id, _count, _current_seq);
+
+ } else {
+ _dataman_id = 0;
+ _count = 0;
+ _current_seq = 0;
+ warnx("offboard mission init: ERROR, reading mission state failed");
+ }
+}
+
+/**
+ * Write new mission state to dataman and publish offboard_mission topic to notify navigator about changes.
+ */
+int
+MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int seq)
+{
+ struct mission_s mission;
+
+ mission.dataman_id = dataman_id;
+ mission.count = count;
+ mission.current_seq = seq;
+
+ /* update mission state in dataman */
+ int res = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s));
+
+ if (res == sizeof(mission_s)) {
+ /* update active mission state */
+ _dataman_id = dataman_id;
+ _count = count;
+ _current_seq = seq;
+
+ /* mission state saved successfully, publish offboard_mission topic */
+ if (_offboard_mission_pub < 0) {
+ _offboard_mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission);
+
+ } else {
+ orb_publish(ORB_ID(offboard_mission), _offboard_mission_pub, &mission);
+ }
+
+ return OK;
+
+ } else {
+ warnx("ERROR: can't save mission state");
+ _mavlink->send_statustext(MAV_SEVERITY_CRITICAL, "ERROR: can't save mission state");
+
+ return ERROR;
+ }
+}
+
+void
+MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type)
+{
+ mavlink_message_t msg;
+ mavlink_mission_ack_t wpa;
+
+ wpa.target_system = sysid;
+ wpa.target_component = compid;
+ wpa.type = type;
+
+ mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpa);
+ _mavlink->send_message(&msg);
+
+ if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); }
+}
+
+
+void
+MavlinkMissionManager::send_mission_current(uint16_t seq)
+{
+ if (seq < _count) {
+ mavlink_message_t msg;
+ mavlink_mission_current_t wpc;
+
+ wpc.seq = seq;
+
+ mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc);
+ _mavlink->send_message(&msg);
+
+ } else if (seq == 0 && _count == 0) {
+ /* don't broadcast if no WPs */
+
+ } else {
+ if (_verbose) { warnx("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq); }
+
+ _mavlink->send_statustext_critical("ERROR: wp index out of bounds");
+ }
+}
+
+
+void
+MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count)
+{
+ _time_last_sent = hrt_absolute_time();
+
+ mavlink_message_t msg;
+ mavlink_mission_count_t wpc;
+
+ wpc.target_system = sysid;
+ wpc.target_component = compid;
+ wpc.count = _count;
+
+ mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc);
+ _mavlink->send_message(&msg);
+
+ if (_verbose) { warnx("WPM: Send MISSION_COUNT %u to ID %u", wpc.count, wpc.target_system); }
+}
+
+
+void
+MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq)
+{
+ dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_dataman_id);
+ struct mission_item_s mission_item;
+
+ if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) {
+ _time_last_sent = hrt_absolute_time();
+
+ /* create mission_item_s from mavlink_mission_item_t */
+ mavlink_mission_item_t wp;
+ format_mavlink_mission_item(&mission_item, &wp);
+
+ mavlink_message_t msg;
+ wp.target_system = sysid;
+ wp.target_component = compid;
+ wp.seq = seq;
+ wp.current = (_current_seq == seq) ? 1 : 0;
+ mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp);
+ _mavlink->send_message(&msg);
+
+ if (_verbose) { warnx("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); }
+
+ } else {
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ _mavlink->send_statustext_critical("Unable to read from micro SD");
+
+ if (_verbose) { warnx("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); }
+ }
+}
+
+
+void
+MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq)
+{
+ if (seq < _max_count) {
+ _time_last_sent = hrt_absolute_time();
+
+ mavlink_message_t msg;
+ mavlink_mission_request_t wpr;
+ wpr.target_system = sysid;
+ wpr.target_component = compid;
+ wpr.seq = seq;
+ mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpr);
+ _mavlink->send_message(&msg);
+
+ if (_verbose) { warnx("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); }
+
+ } else {
+ _mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity");
+
+ if (_verbose) { warnx("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq); }
+ }
+}
+
+
+void
+MavlinkMissionManager::send_mission_item_reached(uint16_t seq)
+{
+ mavlink_message_t msg;
+ mavlink_mission_item_reached_t wp_reached;
+
+ wp_reached.seq = seq;
+
+ mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp_reached);
+ _mavlink->send_message(&msg);
+
+ if (_verbose) { warnx("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); }
+}
+
+
+void
+MavlinkMissionManager::eventloop()
+{
+ hrt_abstime now = hrt_absolute_time();
+
+ bool updated = false;
+ orb_check(_mission_result_sub, &updated);
+
+ if (updated) {
+ mission_result_s mission_result;
+ orb_copy(ORB_ID(mission_result), _mission_result_sub, &mission_result);
+
+ _current_seq = mission_result.seq_current;
+
+ if (_verbose) { warnx("WPM: got mission result, new current_seq: %d", _current_seq); }
+
+ if (mission_result.reached) {
+ send_mission_item_reached((uint16_t)mission_result.seq_reached);
+ }
+
+ send_mission_current(_current_seq);
+
+ } else {
+ if (_slow_rate_limiter.check(now)) {
+ send_mission_current(_current_seq);
+ }
+ }
+
+ /* check for timed-out operations */
+ if (_state != MAVLINK_WPM_STATE_IDLE && hrt_elapsed_time(&_time_last_recv) > _action_timeout) {
+ _mavlink->send_statustext_critical("Operation timeout");
+
+ if (_verbose) { warnx("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state); }
+
+ _state = MAVLINK_WPM_STATE_IDLE;
+
+ } else if (_state == MAVLINK_WPM_STATE_GETLIST && hrt_elapsed_time(&_time_last_sent) > _retry_timeout) {
+ /* try to request item again after timeout */
+ send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
+
+ } else if (_state == MAVLINK_WPM_STATE_SENDLIST && hrt_elapsed_time(&_time_last_sent) > _retry_timeout) {
+ if (_transfer_seq == 0) {
+ /* try to send items count again after timeout */
+ send_mission_count(_transfer_partner_sysid, _transfer_partner_compid, _transfer_count);
+
+ } else {
+ /* try to send item again after timeout */
+ send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq - 1);
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_message(const mavlink_message_t *msg)
+{
+ switch (msg->msgid) {
+ case MAVLINK_MSG_ID_MISSION_ACK:
+ handle_mission_ack(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_SET_CURRENT:
+ handle_mission_set_current(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
+ handle_mission_request_list(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_REQUEST:
+ handle_mission_request(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_COUNT:
+ handle_mission_count(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_ITEM:
+ handle_mission_item(msg);
+ break;
+
+ case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
+ handle_mission_clear_all(msg);
+ break;
+
+ default:
+ break;
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg)
+{
+ mavlink_mission_ack_t wpa;
+ mavlink_msg_mission_ack_decode(msg, &wpa);
+
+ if (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/) {
+ if ((msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid)) {
+ if (_state == MAVLINK_WPM_STATE_SENDLIST) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (_transfer_seq == _count) {
+ if (_verbose) { warnx("WPM: MISSION_ACK OK all items sent, switch to state IDLE"); }
+
+ } else {
+ _mavlink->send_statustext_critical("WPM: ERR: not all items sent -> IDLE");
+
+ if (_verbose) { warnx("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway"); }
+ }
+
+ _state = MAVLINK_WPM_STATE_IDLE;
+ }
+
+ } else {
+ _mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch");
+
+ if (_verbose) { warnx("WPM: MISSION_ACK ERROR: rejected, partner ID mismatch"); }
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg)
+{
+ mavlink_mission_set_current_t wpc;
+ mavlink_msg_mission_set_current_decode(msg, &wpc);
+
+ if (wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) {
+ if (_state == MAVLINK_WPM_STATE_IDLE) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (wpc.seq < _count) {
+ if (update_active_mission(_dataman_id, _count, wpc.seq) == OK) {
+ if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d OK", wpc.seq); }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq); }
+
+ _mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID");
+ }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); }
+
+ _mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list");
+ }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: busy"); }
+
+ _mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy");
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg)
+{
+ mavlink_mission_request_list_t wprl;
+ mavlink_msg_mission_request_list_decode(msg, &wprl);
+
+ if (wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) {
+ if (_state == MAVLINK_WPM_STATE_IDLE || _state == MAVLINK_WPM_STATE_SENDLIST) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (_count > 0) {
+ _state = MAVLINK_WPM_STATE_SENDLIST;
+ _transfer_seq = 0;
+ _transfer_count = _count;
+ _transfer_partner_sysid = msg->sysid;
+ _transfer_partner_compid = msg->compid;
+
+ if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST OK, %u mission items to send", _transfer_count); }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty"); }
+
+ _mavlink->send_statustext_info("WPM: mission is empty");
+ }
+
+ send_mission_count(msg->sysid, msg->compid, _count);
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST ERROR: busy"); }
+
+ _mavlink->send_statustext_critical("IGN REQUEST LIST: Busy");
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg)
+{
+ mavlink_mission_request_t wpr;
+ mavlink_msg_mission_request_decode(msg, &wpr);
+
+ if (wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) {
+ if (msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid) {
+ if (_state == MAVLINK_WPM_STATE_SENDLIST) {
+ _time_last_recv = hrt_absolute_time();
+
+ /* _transfer_seq contains sequence of expected request */
+ if (wpr.seq == _transfer_seq && _transfer_seq < _transfer_count) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u", wpr.seq, msg->sysid); }
+
+ _transfer_seq++;
+
+ } else if (wpr.seq == _transfer_seq - 1) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u (again)", wpr.seq, msg->sysid); }
+
+ } else {
+ if (_transfer_seq > 0 && _transfer_seq < _transfer_count) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid, _transfer_seq - 1, _transfer_seq); }
+
+ } else if (_transfer_seq <= 0) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq); }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq - 1); }
+ }
+
+ _state = MAVLINK_WPM_STATE_IDLE;
+
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected");
+ return;
+ }
+
+ /* double check bounds in case of items count changed */
+ if (wpr.seq < _count) {
+ send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq);
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bound [%u, %u]", (unsigned)wpr.seq, (unsigned)wpr.seq, (unsigned)_count - 1); }
+
+ _state = MAVLINK_WPM_STATE_IDLE;
+
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected");
+ }
+
+ } else if (_state == MAVLINK_WPM_STATE_IDLE) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: no transfer"); }
+
+ _mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST: No active transfer");
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: busy (state %d).", _state); }
+
+ _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
+ }
+
+ } else {
+ _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch");
+
+ if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: rejected, partner ID mismatch"); }
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg)
+{
+ mavlink_mission_count_t wpc;
+ mavlink_msg_mission_count_decode(msg, &wpc);
+
+ if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) {
+ if (_state == MAVLINK_WPM_STATE_IDLE) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (wpc.count > _max_count) {
+ if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, _max_count); }
+
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_NO_SPACE);
+ return;
+ }
+
+ if (wpc.count == 0) {
+ if (_verbose) { warnx("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); }
+
+ /* alternate dataman ID anyway to let navigator know about changes */
+ update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0);
+ _mavlink->send_statustext_info("WPM: COUNT 0: CLEAR MISSION");
+
+ // TODO send ACK?
+ return;
+ }
+
+ if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); }
+
+ _state = MAVLINK_WPM_STATE_GETLIST;
+ _transfer_seq = 0;
+ _transfer_partner_sysid = msg->sysid;
+ _transfer_partner_compid = msg->compid;
+ _transfer_count = wpc.count;
+ _transfer_dataman_id = _dataman_id == 0 ? 1 : 0; // use inactive storage for transmission
+ _transfer_current_seq = -1;
+
+ } else if (_state == MAVLINK_WPM_STATE_GETLIST) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (_transfer_seq == 0) {
+ /* looks like our MISSION_REQUEST was lost, try again */
+ if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid); }
+
+ _mavlink->send_statustext_info("WP CMD OK TRY AGAIN");
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); }
+
+ _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy");
+ return;
+ }
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _state); }
+
+ _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy");
+ return;
+ }
+
+ send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg)
+{
+ mavlink_mission_item_t wp;
+ mavlink_msg_mission_item_decode(msg, &wp);
+
+ if (wp.target_system == mavlink_system.sysid && wp.target_component == _comp_id) {
+ if (_state == MAVLINK_WPM_STATE_GETLIST) {
+ _time_last_recv = hrt_absolute_time();
+
+ if (wp.seq != _transfer_seq) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _transfer_seq); }
+
+ /* don't send request here, it will be performed in eventloop after timeout */
+ return;
+ }
+
+ } else if (_state == MAVLINK_WPM_STATE_IDLE) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: no transfer"); }
+
+ _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer");
+ return;
+
+ } else {
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: busy, state %i", _state); }
+
+ _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy");
+ return;
+ }
+
+ struct mission_item_s mission_item;
+ int ret = parse_mavlink_mission_item(&wp, &mission_item);
+
+ if (ret != OK) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); }
+
+ _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy");
+
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret);
+ _state = MAVLINK_WPM_STATE_IDLE;
+ return;
+ }
+
+ dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_transfer_dataman_id);
+
+ if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) {
+ if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); }
+
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ _mavlink->send_statustext_critical("Unable to write on micro SD");
+ _state = MAVLINK_WPM_STATE_IDLE;
+ return;
+ }
+
+ /* waypoint marked as current */
+ if (wp.current) {
+ _transfer_current_seq = wp.seq;
+ }
+
+ if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); }
+
+ _transfer_seq = wp.seq + 1;
+
+ if (_transfer_seq == _transfer_count) {
+ /* got all new mission items successfully */
+ if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE", _transfer_count, _transfer_current_seq); }
+
+ _mavlink->send_statustext_info("WPM: Transfer complete.");
+
+ _state = MAVLINK_WPM_STATE_IDLE;
+
+ if (update_active_mission(_transfer_dataman_id, _transfer_count, _transfer_current_seq) == OK) {
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED);
+
+ } else {
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ }
+
+ } else {
+ /* request next item */
+ send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq);
+ }
+ }
+}
+
+
+void
+MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg)
+{
+ mavlink_mission_clear_all_t wpca;
+ mavlink_msg_mission_clear_all_decode(msg, &wpca);
+
+ if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) {
+
+ if (_state == MAVLINK_WPM_STATE_IDLE) {
+ /* don't touch mission items storage itself, but only items count in mission state */
+ _time_last_recv = hrt_absolute_time();
+
+ if (update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0) == OK) {
+ if (_verbose) { warnx("WPM: CLEAR_ALL OK"); }
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED);
+
+ } else {
+ send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR);
+ }
+
+ } else {
+ _mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy");
+
+ if (_verbose) { warnx("WPM: CLEAR_ALL IGNORED: busy"); }
+ }
+ }
+}
+
+int
+MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item)
+{
+ /* only support global waypoints for now */
+ switch (mavlink_mission_item->frame) {
+ case MAV_FRAME_GLOBAL:
+ mission_item->lat = (double)mavlink_mission_item->x;
+ mission_item->lon = (double)mavlink_mission_item->y;
+ mission_item->altitude = mavlink_mission_item->z;
+ mission_item->altitude_is_relative = false;
+ break;
+
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ mission_item->lat = (double)mavlink_mission_item->x;
+ mission_item->lon = (double)mavlink_mission_item->y;
+ mission_item->altitude = mavlink_mission_item->z;
+ mission_item->altitude_is_relative = true;
+ break;
+
+ case MAV_FRAME_LOCAL_NED:
+ case MAV_FRAME_LOCAL_ENU:
+ return MAV_MISSION_UNSUPPORTED_FRAME;
+
+ case MAV_FRAME_MISSION:
+ default:
+ return MAV_MISSION_ERROR;
+ }
+
+ switch (mavlink_mission_item->command) {
+ case MAV_CMD_NAV_TAKEOFF:
+ mission_item->pitch_min = mavlink_mission_item->param1;
+ break;
+ case MAV_CMD_DO_JUMP:
+ mission_item->do_jump_mission_index = mavlink_mission_item->param1;
+ mission_item->do_jump_current_count = 0;
+ mission_item->do_jump_repeat_count = mavlink_mission_item->param2;
+ break;
+ default:
+ mission_item->acceptance_radius = mavlink_mission_item->param2;
+ mission_item->time_inside = mavlink_mission_item->param1;
+ break;
+ }
+
+ mission_item->yaw = _wrap_pi(mavlink_mission_item->param4 * M_DEG_TO_RAD_F);
+ mission_item->loiter_radius = fabsf(mavlink_mission_item->param3);
+ mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */
+ mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command;
+
+ mission_item->autocontinue = mavlink_mission_item->autocontinue;
+ // mission_item->index = mavlink_mission_item->seq;
+ mission_item->origin = ORIGIN_MAVLINK;
+
+ /* reset DO_JUMP count */
+ mission_item->do_jump_current_count = 0;
+
+ return MAV_MISSION_ACCEPTED;
+}
+
+
+int
+MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
+{
+ if (mission_item->altitude_is_relative) {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
+
+ } else {
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ }
+
+ switch (mission_item->nav_cmd) {
+ case NAV_CMD_TAKEOFF:
+ mavlink_mission_item->param1 = mission_item->pitch_min;
+ break;
+
+ case NAV_CMD_DO_JUMP:
+ mavlink_mission_item->param1 = mission_item->do_jump_mission_index;
+ mavlink_mission_item->param2 = mission_item->do_jump_repeat_count;
+ break;
+
+ default:
+ mavlink_mission_item->param2 = mission_item->acceptance_radius;
+ mavlink_mission_item->param1 = mission_item->time_inside;
+ break;
+ }
+
+ mavlink_mission_item->x = (float)mission_item->lat;
+ mavlink_mission_item->y = (float)mission_item->lon;
+ mavlink_mission_item->z = mission_item->altitude;
+
+ mavlink_mission_item->param4 = mission_item->yaw * M_RAD_TO_DEG_F;
+ mavlink_mission_item->param3 = mission_item->loiter_radius * (float)mission_item->loiter_direction;
+ mavlink_mission_item->command = mission_item->nav_cmd;
+ mavlink_mission_item->autocontinue = mission_item->autocontinue;
+ // mavlink_mission_item->seq = mission_item->index;
+
+ return OK;
+}
diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h
new file mode 100644
index 000000000..f63c32f24
--- /dev/null
+++ b/src/modules/mavlink/mavlink_mission.h
@@ -0,0 +1,177 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mavlink_mission.h
+ * MAVLink mission manager interface definition.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#pragma once
+
+#include "mavlink_bridge_header.h"
+#include "mavlink_rate_limiter.h"
+#include <uORB/uORB.h>
+
+// FIXME XXX - TO BE MOVED TO XML
+enum MAVLINK_WPM_STATES {
+ MAVLINK_WPM_STATE_IDLE = 0,
+ MAVLINK_WPM_STATE_SENDLIST,
+ MAVLINK_WPM_STATE_GETLIST,
+ MAVLINK_WPM_STATE_ENUM_END
+};
+
+enum MAVLINK_WPM_CODES {
+ MAVLINK_WPM_CODE_OK = 0,
+ MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
+ MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
+ MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
+ MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
+ MAVLINK_WPM_CODE_ENUM_END
+};
+
+#define MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds
+#define MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds
+
+class Mavlink;
+
+class MavlinkMissionManager {
+public:
+ MavlinkMissionManager(Mavlink *parent);
+
+ ~MavlinkMissionManager();
+
+ void init_offboard_mission();
+
+ int update_active_mission(int dataman_id, unsigned count, int seq);
+
+ void send_message(mavlink_message_t *msg);
+
+ /**
+ * @brief Sends an waypoint ack message
+ */
+ void send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type);
+
+ /**
+ * @brief Broadcasts the new target waypoint and directs the MAV to fly there
+ *
+ * This function broadcasts its new active waypoint sequence number and
+ * sends a message to the controller, advising it to fly to the coordinates
+ * of the waypoint with a given orientation
+ *
+ * @param seq The waypoint sequence number the MAV should fly to.
+ */
+ void send_mission_current(uint16_t seq);
+
+ void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count);
+
+ void send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq);
+
+ void send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq);
+
+ /**
+ * @brief emits a message that a waypoint reached
+ *
+ * This function broadcasts a message that a waypoint is reached.
+ *
+ * @param seq The waypoint sequence number the MAV has reached.
+ */
+ void send_mission_item_reached(uint16_t seq);
+
+ void eventloop();
+
+ void handle_message(const mavlink_message_t *msg);
+
+ void handle_mission_ack(const mavlink_message_t *msg);
+
+ void handle_mission_set_current(const mavlink_message_t *msg);
+
+ void handle_mission_request_list(const mavlink_message_t *msg);
+
+ void handle_mission_request(const mavlink_message_t *msg);
+
+ void handle_mission_count(const mavlink_message_t *msg);
+
+ void handle_mission_item(const mavlink_message_t *msg);
+
+ void handle_mission_clear_all(const mavlink_message_t *msg);
+
+ /**
+ * Parse mavlink MISSION_ITEM message to get mission_item_s.
+ */
+ int parse_mavlink_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
+
+ /**
+ * Format mission_item_s as mavlink MISSION_ITEM message.
+ */
+ int format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
+
+ void set_verbose(bool v) { _verbose = v; }
+
+private:
+ Mavlink* _mavlink;
+
+ enum MAVLINK_WPM_STATES _state; ///< Current state
+
+ uint64_t _time_last_recv;
+ uint64_t _time_last_sent;
+
+ uint32_t _action_timeout;
+ uint32_t _retry_timeout;
+ unsigned _max_count; ///< Maximum number of mission items
+
+ int _dataman_id; ///< Dataman storage ID for active mission
+ unsigned _count; ///< Count of items in active mission
+ int _current_seq; ///< Current item sequence in active mission
+
+ int _transfer_dataman_id; ///< Dataman storage ID for current transmission
+ unsigned _transfer_count; ///< Items count in current transmission
+ unsigned _transfer_seq; ///< Item sequence in current transmission
+ unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized)
+ unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission
+ unsigned _transfer_partner_compid; ///< Partner component ID for current transmission
+
+ int _offboard_mission_sub;
+ int _mission_result_sub;
+ orb_advert_t _offboard_mission_pub;
+
+ MavlinkRateLimiter _slow_rate_limiter;
+
+ bool _verbose;
+
+ mavlink_channel_t _channel;
+ uint8_t _comp_id;
+};
diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp
index 21d5219d3..734f0903a 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.cpp
+++ b/src/modules/mavlink/mavlink_orb_subscription.cpp
@@ -47,53 +47,58 @@
#include "mavlink_orb_subscription.h"
MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) :
- _fd(orb_subscribe(_topic)),
- _published(false),
+ next(nullptr),
_topic(topic),
- _last_check(0),
- next(nullptr)
+ _fd(orb_subscribe(_topic)),
+ _published(false)
{
- _data = malloc(topic->o_size);
- memset(_data, 0, topic->o_size);
}
MavlinkOrbSubscription::~MavlinkOrbSubscription()
{
close(_fd);
- free(_data);
}
orb_id_t
-MavlinkOrbSubscription::get_topic()
+MavlinkOrbSubscription::get_topic() const
{
return _topic;
}
-void *
-MavlinkOrbSubscription::get_data()
-{
- return _data;
-}
-
bool
-MavlinkOrbSubscription::update(const hrt_abstime t)
+MavlinkOrbSubscription::update(uint64_t *time, void* data)
{
- if (_last_check == t) {
- /* already checked right now, return result of the check */
- return _updated;
+ // TODO this is NOT atomic operation, we can get data newer than time
+ // if topic was published between orb_stat and orb_copy calls.
- } else {
- _last_check = t;
- orb_check(_fd, &_updated);
+ uint64_t time_topic;
+ if (orb_stat(_fd, &time_topic)) {
+ /* error getting last topic publication time */
+ time_topic = 0;
+ }
- if (_updated) {
- orb_copy(_topic, _fd, _data);
- _published = true;
+ if (orb_copy(_topic, _fd, data)) {
+ /* error copying topic data */
+ memset(data, 0, _topic->o_size);
+ return false;
+
+ } else {
+ /* data copied successfully */
+ _published = true;
+ if (time_topic != *time) {
+ *time = time_topic;
return true;
+
+ } else {
+ return false;
}
}
+}
- return false;
+bool
+MavlinkOrbSubscription::update(void* data)
+{
+ return !orb_copy(_topic, _fd, data);
}
bool
diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h
index 8c09772c8..71efb43af 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.h
+++ b/src/modules/mavlink/mavlink_orb_subscription.h
@@ -48,12 +48,26 @@
class MavlinkOrbSubscription
{
public:
- MavlinkOrbSubscription *next; /*< pointer to next subscription in list */
+ MavlinkOrbSubscription *next; ///< pointer to next subscription in list
MavlinkOrbSubscription(const orb_id_t topic);
~MavlinkOrbSubscription();
- bool update(const hrt_abstime t);
+ /**
+ * Check if subscription updated and get data.
+ *
+ * @return true only if topic was updated and data copied to buffer successfully.
+ * If topic was not updated since last check it will return false but still copy the data.
+ * If no data available data buffer will be filled with zeroes.
+ */
+ bool update(uint64_t *time, void* data);
+
+ /**
+ * Copy topic data to given buffer.
+ *
+ * @return true only if topic data copied successfully.
+ */
+ bool update(void* data);
/**
* Check if the topic has been published.
@@ -62,16 +76,12 @@ public:
* @return true if the topic has been published at least once.
*/
bool is_published();
- void *get_data();
- orb_id_t get_topic();
+ orb_id_t get_topic() const;
private:
- const orb_id_t _topic; /*< topic metadata */
- int _fd; /*< subscription handle */
- bool _published; /*< topic was ever published */
- void *_data; /*< pointer to data buffer */
- hrt_abstime _last_check; /*< time of last check */
- bool _updated; /*< updated on last check */
+ const orb_id_t _topic; ///< topic metadata
+ int _fd; ///< subscription handle
+ bool _published; ///< topic was ever published
};
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 98a7cef5a..75d3b6ce4 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -79,7 +79,6 @@ __BEGIN_DECLS
#include "mavlink_bridge_header.h"
#include "mavlink_receiver.h"
#include "mavlink_main.h"
-#include "util.h"
__END_DECLS
@@ -102,16 +101,28 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_cmd_pub(-1),
_flow_pub(-1),
_offboard_control_sp_pub(-1),
+ _local_pos_sp_pub(-1),
+ _global_vel_sp_pub(-1),
+ _att_sp_pub(-1),
+ _rates_sp_pub(-1),
_vicon_position_pub(-1),
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
+ _telemetry_heartbeat_time(0),
+ _radio_status_available(false),
+ _control_mode_sub(-1),
_hil_frames(0),
_old_timestamp(0),
_hil_local_proj_inited(0),
_hil_local_alt0(0.0)
{
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
memset(&hil_local_pos, 0, sizeof(hil_local_pos));
+ memset(&_control_mode, 0, sizeof(_control_mode));
+
+ // make sure the FTP server is started
+ (void)MavlinkFTP::getServer();
}
MavlinkReceiver::~MavlinkReceiver()
@@ -150,6 +161,18 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_manual_control(msg);
break;
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ handle_message_heartbeat(msg);
+ break;
+
+ case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
+ handle_message_request_data_stream(msg);
+ break;
+
+ case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
+ MavlinkFTP::getServer()->handle_message(_mavlink, msg);
+ break;
+
default:
break;
}
@@ -342,53 +365,21 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
void
MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
{
- mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
- mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
+ mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
+ mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control);
- if (mavlink_system.sysid < 4) {
+ /* Only accept system IDs from 1 to 4 */
+ if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) {
struct offboard_control_setpoint_s offboard_control_sp;
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));
- uint8_t ml_mode = 0;
- bool ml_armed = false;
-
- switch (quad_motors_setpoint.mode) {
- case 0:
- ml_armed = false;
- break;
-
- case 1:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
- ml_armed = true;
-
- break;
-
- case 2:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
- ml_armed = true;
-
- break;
-
- case 3:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
- break;
-
- case 4:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
- break;
- }
-
- offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
+ /* Convert values * 1000 back */
+ offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
- if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
- ml_armed = false;
- }
-
- offboard_control_sp.armed = ml_armed;
- offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);
+ offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
offboard_control_sp.timestamp = hrt_absolute_time();
@@ -404,27 +395,34 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
void
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
{
- mavlink_radio_status_t rstatus;
- mavlink_msg_radio_status_decode(msg, &rstatus);
-
- struct telemetry_status_s tstatus;
- memset(&tstatus, 0, sizeof(tstatus));
-
- tstatus.timestamp = hrt_absolute_time();
- tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
- tstatus.rssi = rstatus.rssi;
- tstatus.remote_rssi = rstatus.remrssi;
- tstatus.txbuf = rstatus.txbuf;
- tstatus.noise = rstatus.noise;
- tstatus.remote_noise = rstatus.remnoise;
- tstatus.rxerrors = rstatus.rxerrors;
- tstatus.fixed = rstatus.fixed;
+ /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
+ if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) {
+ mavlink_radio_status_t rstatus;
+ mavlink_msg_radio_status_decode(msg, &rstatus);
+
+ struct telemetry_status_s tstatus;
+ memset(&tstatus, 0, sizeof(tstatus));
+
+ tstatus.timestamp = hrt_absolute_time();
+ tstatus.heartbeat_time = _telemetry_heartbeat_time;
+ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
+ tstatus.rssi = rstatus.rssi;
+ tstatus.remote_rssi = rstatus.remrssi;
+ tstatus.txbuf = rstatus.txbuf;
+ tstatus.noise = rstatus.noise;
+ tstatus.remote_noise = rstatus.remnoise;
+ tstatus.rxerrors = rstatus.rxerrors;
+ tstatus.fixed = rstatus.fixed;
+
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
- if (_telemetry_status_pub < 0) {
- _telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
+ }
- } else {
- orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);
+ /* this means that heartbeats alone won't be published to the radio status no more */
+ _radio_status_available = true;
}
}
@@ -443,6 +441,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
manual.r = man.r / 1000.0f;
manual.z = man.z / 1000.0f;
+ warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z);
+
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
@@ -452,6 +452,57 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
+{
+ /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
+ if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) {
+ mavlink_heartbeat_t hb;
+ mavlink_msg_heartbeat_decode(msg, &hb);
+
+ /* ignore own heartbeats, accept only heartbeats from GCS */
+ if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) {
+ _telemetry_heartbeat_time = hrt_absolute_time();
+
+ /* if no radio status messages arrive, lets at least publish that heartbeats were received */
+ if (!_radio_status_available) {
+
+ struct telemetry_status_s tstatus;
+ memset(&tstatus, 0, sizeof(tstatus));
+
+ tstatus.timestamp = _telemetry_heartbeat_time;
+ tstatus.heartbeat_time = _telemetry_heartbeat_time;
+ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
+
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
+
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
+ }
+ }
+ }
+ }
+}
+
+void
+MavlinkReceiver::handle_message_request_data_stream(mavlink_message_t *msg)
+{
+ mavlink_request_data_stream_t req;
+ mavlink_msg_request_data_stream_decode(msg, &req);
+
+ if (req.target_system == mavlink_system.sysid && req.target_component == mavlink_system.compid) {
+ float rate = req.start_stop ? (1000.0f / req.req_message_rate) : 0.0f;
+
+ MavlinkStream *stream;
+ LL_FOREACH(_mavlink->get_streams(), stream) {
+ if (req.req_stream_id == stream->get_id()) {
+ _mavlink->configure_stream_threadsafe(stream->get_name(), rate);
+ }
+ }
+ }
+}
+
+void
MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg)
{
mavlink_hil_sensor_t imu;
@@ -667,12 +718,11 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.lat = gps.lat;
hil_gps.lon = gps.lon;
hil_gps.alt = gps.alt;
- hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
- hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
+ hil_gps.eph = (float)gps.eph * 1e-2f; // from cm to m
+ hil_gps.epv = (float)gps.epv * 1e-2f; // from cm to m
hil_gps.timestamp_variance = timestamp;
hil_gps.s_variance_m_s = 5.0f;
- hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
hil_gps.timestamp_velocity = timestamp;
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
@@ -682,9 +732,8 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg)
hil_gps.vel_ned_valid = true;
hil_gps.cog_rad = _wrap_pi(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
- hil_gps.timestamp_satellites = timestamp;
hil_gps.fix_type = gps.fix_type;
- hil_gps.satellites_visible = gps.satellites_visible;
+ hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used?
if (_gps_pub < 0) {
_gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps);
@@ -902,16 +951,8 @@ MavlinkReceiver::receive_thread(void *arg)
/* handle generic messages and commands */
handle_message(&msg);
- /* handle packet with waypoint component */
- _mavlink->mavlink_wpm_message_handler(&msg);
-
- /* handle packet with parameter component */
- _mavlink->mavlink_pm_message_handler(_mavlink->get_channel(), &msg);
-
- if (_mavlink->get_forwarding_on()) {
- /* forward any messages to other mavlink instances */
- Mavlink::forward_message(&msg, _mavlink);
- }
+ /* handle packet with parent object */
+ _mavlink->handle_message(&msg);
}
}
}
@@ -952,7 +993,6 @@ MavlinkReceiver::receive_start(Mavlink *parent)
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
pthread_attr_setstacksize(&receiveloop_attr, 2900);
-
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 9ab84b58a..8d38b9973 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -36,6 +36,7 @@
* MAVLink 1.0 uORB listener definition
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#pragma once
@@ -44,6 +45,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -53,6 +55,7 @@
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
@@ -68,6 +71,8 @@
#include <uORB/topics/airspeed.h>
#include <uORB/topics/battery_status.h>
+#include "mavlink_ftp.h"
+
class Mavlink;
class MavlinkReceiver
@@ -100,8 +105,6 @@ public:
static void *start_helper(void *context);
private:
- perf_counter_t _loop_perf; /**< loop performance counter */
-
Mavlink *_mavlink;
void handle_message(mavlink_message_t *msg);
@@ -112,6 +115,8 @@ private:
void handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg);
void handle_message_radio_status(mavlink_message_t *msg);
void handle_message_manual_control(mavlink_message_t *msg);
+ void handle_message_heartbeat(mavlink_message_t *msg);
+ void handle_message_request_data_stream(mavlink_message_t *msg);
void handle_message_hil_sensor(mavlink_message_t *msg);
void handle_message_hil_gps(mavlink_message_t *msg);
void handle_message_hil_state_quaternion(mavlink_message_t *msg);
@@ -120,6 +125,7 @@ private:
mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos;
+ struct vehicle_control_mode_s _control_mode;
orb_advert_t _global_pos_pub;
orb_advert_t _local_pos_pub;
orb_advert_t _attitude_pub;
@@ -134,10 +140,17 @@ private:
orb_advert_t _cmd_pub;
orb_advert_t _flow_pub;
orb_advert_t _offboard_control_sp_pub;
+ orb_advert_t _local_pos_sp_pub;
+ orb_advert_t _global_vel_sp_pub;
+ orb_advert_t _att_sp_pub;
+ orb_advert_t _rates_sp_pub;
orb_advert_t _vicon_position_pub;
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
+ hrt_abstime _telemetry_heartbeat_time;
+ bool _radio_status_available;
+ int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;
bool _hil_local_proj_inited;
diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp
index 5ec30bd33..7279206db 100644
--- a/src/modules/mavlink/mavlink_stream.cpp
+++ b/src/modules/mavlink/mavlink_stream.cpp
@@ -43,7 +43,11 @@
#include "mavlink_stream.h"
#include "mavlink_main.h"
-MavlinkStream::MavlinkStream() : _interval(1000000), _last_sent(0), _channel(MAVLINK_COMM_0), next(nullptr)
+MavlinkStream::MavlinkStream() :
+ next(nullptr),
+ _channel(MAVLINK_COMM_0),
+ _interval(1000000),
+ _last_sent(0)
{
}
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index 2979d20de..69809a386 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -50,14 +50,6 @@ class MavlinkStream;
class MavlinkStream
{
-private:
- hrt_abstime _last_sent;
-
-protected:
- mavlink_channel_t _channel;
- unsigned int _interval;
-
- virtual void send(const hrt_abstime t) = 0;
public:
MavlinkStream *next;
@@ -71,9 +63,20 @@ public:
* @return 0 if updated / sent, -1 if unchanged
*/
int update(const hrt_abstime t);
- virtual MavlinkStream *new_instance() = 0;
+ static MavlinkStream *new_instance();
+ static const char *get_name_static();
virtual void subscribe(Mavlink *mavlink) = 0;
- virtual const char *get_name() = 0;
+ virtual const char *get_name() const = 0;
+ virtual uint8_t get_id() = 0;
+
+protected:
+ mavlink_channel_t _channel;
+ unsigned int _interval;
+
+ virtual void send(const hrt_abstime t) = 0;
+
+private:
+ hrt_abstime _last_sent;
};
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index f532e26fe..d49bbb7f7 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -39,11 +39,13 @@ MODULE_COMMAND = mavlink
SRCS += mavlink_main.cpp \
mavlink.c \
mavlink_receiver.cpp \
+ mavlink_mission.cpp \
mavlink_orb_subscription.cpp \
mavlink_messages.cpp \
mavlink_stream.cpp \
mavlink_rate_limiter.cpp \
- mavlink_commands.cpp
+ mavlink_commands.cpp \
+ mavlink_ftp.cpp
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h
deleted file mode 100644
index 532eff7aa..000000000
--- a/src/modules/mavlink/waypoints.h
+++ /dev/null
@@ -1,111 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2009-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 waypoints.h
- * MAVLink waypoint protocol definition (BSD-relicensed).
- *
- * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- */
-
-#ifndef WAYPOINTS_H_
-#define WAYPOINTS_H_
-
-/* This assumes you have the mavlink headers on your include path
- or in the same folder as this source file */
-
-#include <v1.0/mavlink_types.h>
-#include "mavlink_bridge_header.h"
-#include <stdbool.h>
-#include <uORB/topics/mission.h>
-
-enum MAVLINK_WPM_STATES {
- MAVLINK_WPM_STATE_IDLE = 0,
- MAVLINK_WPM_STATE_SENDLIST,
- MAVLINK_WPM_STATE_SENDLIST_SENDWPS,
- MAVLINK_WPM_STATE_GETLIST,
- MAVLINK_WPM_STATE_GETLIST_GETWPS,
- MAVLINK_WPM_STATE_GETLIST_GOTALL,
- MAVLINK_WPM_STATE_ENUM_END
-};
-
-enum MAVLINK_WPM_CODES {
- MAVLINK_WPM_CODE_OK = 0,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS,
- MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED,
- MAVLINK_WPM_CODE_ENUM_END
-};
-
-
-#define MAVLINK_WPM_MAX_WP_COUNT 255
-#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds
-#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint
-#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000
-
-
-struct mavlink_wpm_storage {
- uint16_t size;
- uint16_t max_size;
- enum MAVLINK_WPM_STATES current_state;
- int16_t current_wp_id; ///< Waypoint in current transmission
- uint16_t current_count;
- uint8_t current_partner_sysid;
- uint8_t current_partner_compid;
- uint64_t timestamp_lastaction;
- uint64_t timestamp_last_send_setpoint;
- uint32_t timeout;
- int current_dataman_id;
-};
-
-typedef struct mavlink_wpm_storage mavlink_wpm_storage;
-
-int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item);
-int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item);
-
-
-void mavlink_wpm_init(mavlink_wpm_storage *state);
-void mavlink_waypoint_eventloop(uint64_t now);
-void mavlink_wpm_message_handler(const mavlink_message_t *msg);
-
-extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1,
- float param2, float param3, float param4, float param5_lat_x,
- float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command);
-
-static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
-
-#endif /* WAYPOINTS_H_ */
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 20e016da3..19c10198c 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -72,6 +72,7 @@
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
+#include <systemlib/circuit_breaker.h>
#include <lib/mathlib/mathlib.h>
#include <lib/geo/geo.h>
@@ -123,6 +124,8 @@ private:
orb_advert_t _v_rates_sp_pub; /**< rate setpoint publication */
orb_advert_t _actuators_0_pub; /**< attitude actuator controls publication */
+ bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
+
struct vehicle_attitude_s _v_att; /**< vehicle attitude */
struct vehicle_attitude_setpoint_s _v_att_sp; /**< vehicle attitude setpoint */
struct vehicle_rates_setpoint_s _v_rates_sp; /**< vehicle rates setpoint */
@@ -267,6 +270,8 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_v_rates_sp_pub(-1),
_actuators_0_pub(-1),
+ _actuators_0_circuit_breaker_enabled(false),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mc_att_control"))
@@ -402,6 +407,8 @@ MulticopterAttitudeControl::parameters_update()
param_get(_params_handles.acro_yaw_max, &v);
_params.acro_rate_max(2) = math::radians(v);
+ _actuators_0_circuit_breaker_enabled = circuit_breaker_enabled("CBRK_RATE_CTRL", CBRK_RATE_CTRL_KEY);
+
return OK;
}
@@ -840,11 +847,13 @@ MulticopterAttitudeControl::task_main()
_actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f;
_actuators.timestamp = hrt_absolute_time();
- if (_actuators_0_pub > 0) {
- orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators);
+ if (!_actuators_0_circuit_breaker_enabled) {
+ if (_actuators_0_pub > 0) {
+ orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators);
- } else {
- _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators);
+ } else {
+ _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators);
+ }
}
}
}
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 09960d106..9b0f69226 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -106,33 +106,36 @@ public:
private:
- bool _task_should_exit; /**< if true, task should exit */
+ bool _task_should_exit; /**< if true, task should exit */
int _control_task; /**< task handle for task */
int _mavlink_fd; /**< mavlink fd */
int _att_sub; /**< vehicle attitude subscription */
int _att_sp_sub; /**< vehicle attitude setpoint */
int _control_mode_sub; /**< vehicle control mode subscription */
- int _params_sub; /**< notification of parameter updates */
- int _manual_sub; /**< notification of manual control updates */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
int _arming_sub; /**< arming status of outputs */
int _local_pos_sub; /**< vehicle local position */
- int _pos_sp_triplet_sub; /**< position setpoint triplet */
+ int _pos_sp_triplet_sub; /**< position setpoint triplet */
+ int _local_pos_sp_sub; /**< offboard local position setpoint */
+ int _global_vel_sp_sub; /**< offboard global velocity setpoint */
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */
orb_advert_t _global_vel_sp_pub; /**< vehicle global velocity setpoint publication */
struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
- struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
+ struct manual_control_setpoint_s _manual; /**< r/c channel data */
+ struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */
struct actuator_armed_s _arming; /**< actuator arming status */
- struct vehicle_local_position_s _local_pos; /**< vehicle local position */
+ struct vehicle_local_position_s _local_pos; /**< vehicle local position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */
struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */
struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */
+
struct {
param_t thr_min;
param_t thr_max;
@@ -256,6 +259,7 @@ MulticopterPositionControl::MulticopterPositionControl() :
_arming_sub(-1),
_local_pos_sub(-1),
_pos_sp_triplet_sub(-1),
+ _global_vel_sp_sub(-1),
/* publications */
_att_sp_pub(-1),
@@ -466,7 +470,7 @@ MulticopterPositionControl::update_ref()
{
if (_local_pos.ref_timestamp != _ref_timestamp) {
double lat_sp, lon_sp;
- float alt_sp;
+ float alt_sp = 0.0f;
if (_ref_timestamp != 0) {
/* calculate current position setpoint in global frame */
@@ -528,6 +532,9 @@ MulticopterPositionControl::task_main()
_arming_sub = orb_subscribe(ORB_ID(actuator_armed));
_local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
_pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
+ _local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ _global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
+
parameters_update(true);
@@ -545,10 +552,12 @@ MulticopterPositionControl::task_main()
hrt_abstime t_prev = 0;
const float alt_ctl_dz = 0.2f;
- const float pos_ctl_dz = 0.05f;
math::Vector<3> sp_move_rate;
sp_move_rate.zero();
+
+ float yaw_sp_move_rate;
+
math::Vector<3> thrust_int;
thrust_int.zero();
math::Matrix<3, 3> R;
@@ -664,6 +673,82 @@ MulticopterPositionControl::task_main()
_pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
}
+ } else if (_control_mode.flag_control_offboard_enabled) {
+ /* Offboard control */
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+
+ if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
+
+ _pos_sp(0) = _pos_sp_triplet.current.x;
+ _pos_sp(1) = _pos_sp_triplet.current.y;
+ _pos_sp(2) = _pos_sp_triplet.current.z;
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+
+ } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+ /* move position setpoint with roll/pitch stick */
+ sp_move_rate(0) = _pos_sp_triplet.current.vx;
+ sp_move_rate(1) = _pos_sp_triplet.current.vy;
+ yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed;
+ _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt;
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+
+ /* move altitude setpoint with throttle stick */
+ sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);;
+ }
+
+ /* limit setpoint move rate */
+ float sp_move_norm = sp_move_rate.length();
+
+ if (sp_move_norm > 1.0f) {
+ sp_move_rate /= sp_move_norm;
+ }
+
+ /* scale to max speed and rotate around yaw */
+ math::Matrix<3, 3> R_yaw_sp;
+ R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+ sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
+
+ /* move position setpoint */
+ _pos_sp += sp_move_rate * dt;
+
+ /* check if position setpoint is too far from actual position */
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+
+ } else {
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+
} else {
/* AUTO */
bool updated;
@@ -710,6 +795,7 @@ MulticopterPositionControl::task_main()
_local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp);
}
+
if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid && _pos_sp_triplet.current.type == SETPOINT_TYPE_IDLE) {
/* idle state, don't run controller and set zero thrust */
R.identity();
@@ -753,6 +839,7 @@ MulticopterPositionControl::task_main()
_vel_sp(2) = _params.land_speed;
}
+
if (!_control_mode.flag_control_manual_enabled) {
/* limit 3D speed only in non-manual modes */
float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length();
@@ -862,7 +949,7 @@ MulticopterPositionControl::task_main()
if (_control_mode.flag_control_velocity_enabled) {
/* limit max tilt */
- if (thr_min >= 0.0f && tilt_max < M_PI / 2 - 0.05f) {
+ if (thr_min >= 0.0f && tilt_max < M_PI_F / 2 - 0.05f) {
/* absolute horizontal thrust */
float thrust_sp_xy_len = math::Vector<2>(thrust_sp(0), thrust_sp(1)).length();
@@ -1040,6 +1127,7 @@ MulticopterPositionControl::task_main()
_reset_pos_sp = true;
reset_int_z = true;
reset_int_xy = true;
+
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index bc8dbca50..266215308 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -78,7 +78,7 @@ bool Geofence::inside(const struct vehicle_global_position_s *vehicle)
{
double lat = vehicle->lat / 1e7d;
double lon = vehicle->lon / 1e7d;
- float alt = vehicle->alt;
+ //float alt = vehicle->alt;
return inside(lat, lon, vehicle->alt);
}
@@ -116,9 +116,9 @@ bool Geofence::inside(double lat, double lon, float altitude)
}
// skip vertex 0 (return point)
- if (((temp_vertex_i.lon) >= lon != (temp_vertex_j.lon >= lon)) &&
- (lat <= (temp_vertex_j.lat - temp_vertex_i.lat) * (lon - temp_vertex_i.lon) /
- (temp_vertex_j.lon - temp_vertex_i.lon) + temp_vertex_i.lat)) {
+ if (((double)temp_vertex_i.lon >= lon) != ((double)temp_vertex_j.lon >= lon) &&
+ (lat <= (double)(temp_vertex_j.lat - temp_vertex_i.lat) * (lon - (double)temp_vertex_i.lon) /
+ (double)(temp_vertex_j.lon - temp_vertex_i.lon) + (double)temp_vertex_i.lat)) {
c = !c;
}
@@ -294,4 +294,5 @@ Geofence::loadFromFile(const char *filename)
int Geofence::clearDm()
{
dm_clear(DM_KEY_FENCE_POINTS);
+ return OK;
}
diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp
new file mode 100644
index 000000000..f827e70c9
--- /dev/null
+++ b/src/modules/navigator/loiter.cpp
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * 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 loiter.cpp
+ *
+ * Helper class to loiter
+ *
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "loiter.h"
+#include "navigator.h"
+
+Loiter::Loiter(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name)
+{
+ /* load initial params */
+ updateParams();
+}
+
+Loiter::~Loiter()
+{
+}
+
+void
+Loiter::on_inactive()
+{
+}
+
+void
+Loiter::on_activation()
+{
+ /* set current mission item to loiter */
+ set_loiter_item(&_mission_item);
+
+ /* convert mission item to current setpoint */
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+ pos_sp_triplet->previous.valid = false;
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+Loiter::on_active()
+{
+}
diff --git a/src/modules/navigator/navigator_state.h b/src/modules/navigator/loiter.h
index 476f93414..37ab57a07 100644
--- a/src/modules/navigator/navigator_state.h
+++ b/src/modules/navigator/loiter.h
@@ -1,6 +1,6 @@
-/****************************************************************************
+/***************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -30,26 +30,35 @@
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
-
/**
- * @file navigator_state.h
+ * @file loiter.h
*
- * Navigator state
+ * Helper class to loiter
*
- * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <julian@oes.ch>
*/
-#ifndef NAVIGATOR_STATE_H_
-#define NAVIGATOR_STATE_H_
+#ifndef NAVIGATOR_LOITER_H
+#define NAVIGATOR_LOITER_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Loiter : public MissionBlock
+{
+public:
+ Loiter(Navigator *navigator, const char *name);
+
+ ~Loiter();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
-typedef enum {
- NAV_STATE_NONE = 0,
- NAV_STATE_READY,
- NAV_STATE_LOITER,
- NAV_STATE_MISSION,
- NAV_STATE_RTL,
- NAV_STATE_LAND,
- NAV_STATE_MAX
-} nav_state_t;
+ virtual void on_active();
+};
-#endif /* NAVIGATOR_STATE_H_ */
+#endif
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
new file mode 100644
index 000000000..ba766cd10
--- /dev/null
+++ b/src/modules/navigator/mission.cpp
@@ -0,0 +1,618 @@
+/****************************************************************************
+ *
+ * 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 navigator_mission.cpp
+ *
+ * Helper class to access missions
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <sys/types.h>
+#include <string.h>
+#include <stdlib.h>
+#include <unistd.h>
+
+#include <drivers/drv_hrt.h>
+
+#include <dataman/dataman.h>
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
+#include "mission.h"
+#include "navigator.h"
+
+Mission::Mission(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _param_onboard_enabled(this, "ONBOARD_EN"),
+ _param_takeoff_alt(this, "TAKEOFF_ALT"),
+ _param_dist_1wp(this, "DIST_1WP"),
+ _onboard_mission({0}),
+ _offboard_mission({0}),
+ _current_onboard_mission_index(-1),
+ _current_offboard_mission_index(-1),
+ _need_takeoff(true),
+ _takeoff(false),
+ _mission_result_pub(-1),
+ _mission_result({0}),
+ _mission_type(MISSION_TYPE_NONE),
+ _inited(false),
+ _dist_1wp_ok(false)
+{
+ /* load initial params */
+ updateParams();
+}
+
+Mission::~Mission()
+{
+}
+
+void
+Mission::on_inactive()
+{
+ if (_inited) {
+ /* check if missions have changed so that feedback to ground station is given */
+ bool onboard_updated = false;
+ orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
+ if (onboard_updated) {
+ update_onboard_mission();
+ }
+
+ bool offboard_updated = false;
+ orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
+ if (offboard_updated) {
+ update_offboard_mission();
+ }
+
+ } else {
+ /* read mission topics on initialization */
+ _inited = true;
+
+ update_onboard_mission();
+ update_offboard_mission();
+ }
+
+ if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) {
+ _need_takeoff = true;
+ }
+}
+
+void
+Mission::on_activation()
+{
+ set_mission_items();
+}
+
+void
+Mission::on_active()
+{
+ /* check if anything has changed */
+ bool onboard_updated = false;
+ orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
+ if (onboard_updated) {
+ update_onboard_mission();
+ }
+
+ bool offboard_updated = false;
+ orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated);
+ if (offboard_updated) {
+ update_offboard_mission();
+ }
+
+ /* reset mission items if needed */
+ if (onboard_updated || offboard_updated) {
+ set_mission_items();
+ }
+
+ /* lets check if we reached the current mission item */
+ if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
+ advance_mission();
+ set_mission_items();
+
+ } else {
+ /* if waypoint position reached allow loiter on the setpoint */
+ if (_waypoint_position_reached && _mission_item.nav_cmd != NAV_CMD_IDLE) {
+ _navigator->set_can_loiter_at_sp(true);
+ }
+ }
+}
+
+void
+Mission::update_onboard_mission()
+{
+ if (orb_copy(ORB_ID(onboard_mission), _navigator->get_onboard_mission_sub(), &_onboard_mission) == OK) {
+ /* accept the current index set by the onboard mission if it is within bounds */
+ if (_onboard_mission.current_seq >=0
+ && _onboard_mission.current_seq < (int)_onboard_mission.count) {
+ _current_onboard_mission_index = _onboard_mission.current_seq;
+ } else {
+ /* if less WPs available, reset to first WP */
+ if (_current_onboard_mission_index >= (int)_onboard_mission.count) {
+ _current_onboard_mission_index = 0;
+ /* if not initialized, set it to 0 */
+ } else if (_current_onboard_mission_index < 0) {
+ _current_onboard_mission_index = 0;
+ }
+ /* otherwise, just leave it */
+ }
+
+ } else {
+ _onboard_mission.count = 0;
+ _onboard_mission.current_seq = 0;
+ _current_onboard_mission_index = 0;
+ }
+}
+
+void
+Mission::update_offboard_mission()
+{
+ if (orb_copy(ORB_ID(offboard_mission), _navigator->get_offboard_mission_sub(), &_offboard_mission) == OK) {
+ warnx("offboard mission updated: dataman_id=%d, count=%d, current_seq=%d", _offboard_mission.dataman_id, _offboard_mission.count, _offboard_mission.current_seq);
+ /* determine current index */
+ if (_offboard_mission.current_seq >= 0 && _offboard_mission.current_seq < (int)_offboard_mission.count) {
+ _current_offboard_mission_index = _offboard_mission.current_seq;
+ } else {
+ /* if less items available, reset to first item */
+ if (_current_offboard_mission_index >= (int)_offboard_mission.count) {
+ _current_offboard_mission_index = 0;
+
+ /* if not initialized, set it to 0 */
+ } else if (_current_offboard_mission_index < 0) {
+ _current_offboard_mission_index = 0;
+ }
+ /* otherwise, just leave it */
+ }
+
+ /* Check mission feasibility, for now do not handle the return value,
+ * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
+ dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id);
+
+ missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing,
+ dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(),
+ _navigator->get_home_position()->alt);
+
+ } else {
+ warnx("offboard mission update failed");
+ _offboard_mission.count = 0;
+ _offboard_mission.current_seq = 0;
+ _current_offboard_mission_index = 0;
+ }
+
+ report_current_offboard_mission_item();
+}
+
+
+void
+Mission::advance_mission()
+{
+ if (_takeoff) {
+ _takeoff = false;
+
+ } else {
+ switch (_mission_type) {
+ case MISSION_TYPE_ONBOARD:
+ _current_onboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_OFFBOARD:
+ _current_offboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_NONE:
+ default:
+ break;
+ }
+ }
+}
+
+bool
+Mission::check_dist_1wp()
+{
+ if (_dist_1wp_ok) {
+ /* always return true after at least one successful check */
+ return true;
+ }
+
+ /* check if first waypoint is not too far from home */
+ if (_param_dist_1wp.get() > 0.0f) {
+ if (_navigator->get_vstatus()->condition_home_position_valid) {
+ struct mission_item_s mission_item;
+
+ /* find first waypoint (with lat/lon) item in datamanager */
+ for (unsigned i = 0; i < _offboard_mission.count; i++) {
+ if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id), i,
+ &mission_item, sizeof(mission_item_s)) == sizeof(mission_item_s)) {
+
+ /* check only items with valid lat/lon */
+ if ( mission_item.nav_cmd == NAV_CMD_WAYPOINT ||
+ mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
+ mission_item.nav_cmd == NAV_CMD_TAKEOFF ||
+ mission_item.nav_cmd == NAV_CMD_PATHPLANNING) {
+
+ /* check distance from home to item */
+ float dist_to_1wp = get_distance_to_next_waypoint(
+ mission_item.lat, mission_item.lon,
+ _navigator->get_home_position()->lat, _navigator->get_home_position()->lon);
+
+ if (dist_to_1wp < _param_dist_1wp.get()) {
+ _dist_1wp_ok = true;
+ return true;
+
+ } else {
+ /* item is too far from home */
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "Waypoint too far: %d m,[MIS_DIST_1WP=%d]", (int)dist_to_1wp, (int)_param_dist_1wp.get());
+ return false;
+ }
+ }
+
+ } else {
+ /* error reading, mission is invalid */
+ mavlink_log_info(_navigator->get_mavlink_fd(), "error reading offboard mission");
+ return false;
+ }
+ }
+
+ /* no waypoints found in mission, then we will not fly far away */
+ _dist_1wp_ok = true;
+ return true;
+
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "no home position");
+ return false;
+ }
+
+ } else {
+ return true;
+ }
+}
+
+void
+Mission::set_mission_items()
+{
+ /* make sure param is up to date */
+ updateParams();
+
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* set previous position setpoint to current */
+ set_previous_pos_setpoint();
+
+ /* try setting onboard mission item */
+ if (_param_onboard_enabled.get() && read_mission_item(true, true, &_mission_item)) {
+ /* if mission type changed, notify */
+ if (_mission_type != MISSION_TYPE_ONBOARD) {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running");
+ }
+ _mission_type = MISSION_TYPE_ONBOARD;
+
+ /* try setting offboard mission item */
+ } else if (check_dist_1wp() && read_mission_item(false, true, &_mission_item)) {
+ /* if mission type changed, notify */
+ if (_mission_type != MISSION_TYPE_OFFBOARD) {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running");
+ }
+ _mission_type = MISSION_TYPE_OFFBOARD;
+
+ } else {
+ /* no mission available, switch to loiter */
+ if (_mission_type != MISSION_TYPE_NONE) {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: mission finished");
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: no mission available");
+ }
+ _mission_type = MISSION_TYPE_NONE;
+
+ /* set loiter mission item */
+ set_loiter_item(&_mission_item);
+
+ /* update position setpoint triplet */
+ pos_sp_triplet->previous.valid = false;
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
+
+ reset_mission_item_reached();
+ report_mission_finished();
+
+ _navigator->set_position_setpoint_triplet_updated();
+ return;
+ }
+
+ /* do takeoff on first waypoint for rotary wing vehicles */
+ if (_navigator->get_vstatus()->is_rotary_wing) {
+ /* force takeoff if landed (additional protection) */
+ if (!_takeoff && _navigator->get_vstatus()->condition_landed) {
+ _need_takeoff = true;
+ }
+
+ /* new current mission item set, check if we need takeoff */
+ if (_need_takeoff && (
+ _mission_item.nav_cmd == NAV_CMD_TAKEOFF ||
+ _mission_item.nav_cmd == NAV_CMD_WAYPOINT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
+ _mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH)) {
+ _takeoff = true;
+ _need_takeoff = false;
+ }
+ }
+
+ if (_takeoff) {
+ /* do takeoff before going to setpoint */
+ /* set mission item as next position setpoint */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->next);
+
+ /* calculate takeoff altitude */
+ float takeoff_alt = _mission_item.altitude;
+ if (_mission_item.altitude_is_relative) {
+ takeoff_alt += _navigator->get_home_position()->alt;
+ }
+
+ /* perform takeoff at least to NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
+ if (_navigator->get_vstatus()->condition_landed) {
+ takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get());
+
+ } else {
+ takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get());
+ }
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
+
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude = takeoff_alt;
+ _mission_item.altitude_is_relative = false;
+
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+
+ } else {
+ /* set current position setpoint from mission item */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+
+ /* require takeoff after landing or idle */
+ if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
+ _need_takeoff = true;
+ }
+
+ _navigator->set_can_loiter_at_sp(false);
+ reset_mission_item_reached();
+
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ report_current_offboard_mission_item();
+ }
+ // TODO: report onboard mission item somehow
+
+ /* try to read next mission item */
+ struct mission_item_s mission_item_next;
+
+ if (read_mission_item(_mission_type == MISSION_TYPE_ONBOARD, false, &mission_item_next)) {
+ /* got next mission item, update setpoint triplet */
+ mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next);
+
+ } else {
+ /* next mission item is not available */
+ pos_sp_triplet->next.valid = false;
+ }
+ }
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+bool
+Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item)
+{
+ /* select onboard/offboard mission */
+ int *mission_index_ptr;
+ struct mission_s *mission;
+ dm_item_t dm_item;
+ int mission_index_next;
+
+ if (onboard) {
+ /* onboard mission */
+ mission_index_next = _current_onboard_mission_index + 1;
+ mission_index_ptr = is_current ? &_current_onboard_mission_index : &mission_index_next;
+
+ mission = &_onboard_mission;
+
+ dm_item = DM_KEY_WAYPOINTS_ONBOARD;
+
+ } else {
+ /* offboard mission */
+ mission_index_next = _current_offboard_mission_index + 1;
+ mission_index_ptr = is_current ? &_current_offboard_mission_index : &mission_index_next;
+
+ mission = &_offboard_mission;
+
+ dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id);
+ }
+
+ if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) {
+ /* mission item index out of bounds */
+ return false;
+ }
+
+ /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */
+ for (int i = 0; i < 10; i++) {
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ /* read mission item to temp storage first to not overwrite current mission item if data damaged */
+ struct mission_item_s mission_item_tmp;
+
+ /* read mission item from datamanager */
+ if (dm_read(dm_item, *mission_index_ptr, &mission_item_tmp, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR waypoint could not be read");
+ return false;
+ }
+
+ /* check for DO_JUMP item, and whether it hasn't not already been repeated enough times */
+ if (mission_item_tmp.nav_cmd == NAV_CMD_DO_JUMP) {
+
+ /* do DO_JUMP as many times as requested */
+ if (mission_item_tmp.do_jump_current_count < mission_item_tmp.do_jump_repeat_count) {
+
+ /* only raise the repeat count if this is for the current mission item
+ * but not for the next mission item */
+ if (is_current) {
+ (mission_item_tmp.do_jump_current_count)++;
+ /* save repeat count */
+ if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, &mission_item_tmp, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the
+ * dataman */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR DO JUMP waypoint could not be written");
+ return false;
+ }
+ }
+ /* set new mission item index and repeat
+ * we don't have to validate here, if it's invalid, we should realize this later .*/
+ *mission_index_ptr = mission_item_tmp.do_jump_mission_index;
+
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(),
+ "#audio: DO JUMP repetitions completed");
+ /* no more DO_JUMPS, therefore just try to continue with next mission item */
+ (*mission_index_ptr)++;
+ }
+
+ } else {
+ /* if it's not a DO_JUMP, then we were successful */
+ memcpy(mission_item, &mission_item_tmp, sizeof(struct mission_item_s));
+ return true;
+ }
+ }
+
+ /* we have given up, we don't want to cycle forever */
+ mavlink_log_critical(_navigator->get_mavlink_fd(),
+ "#audio: ERROR DO JUMP is cycling, giving up");
+ return false;
+}
+
+void
+Mission::save_offboard_mission_state()
+{
+ mission_s mission_state;
+
+ /* lock MISSION_STATE item */
+ dm_lock(DM_KEY_MISSION_STATE);
+
+ /* read current state */
+ int read_res = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s));
+
+ if (read_res == sizeof(mission_s)) {
+ /* data read successfully, check dataman ID and items count */
+ if (mission_state.dataman_id == _offboard_mission.dataman_id && mission_state.count == _offboard_mission.count) {
+ /* navigator may modify only sequence, write modified state only if it changed */
+ if (mission_state.current_seq != _current_offboard_mission_index) {
+ if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) {
+ warnx("ERROR: can't save mission state");
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: can't save mission state");
+ }
+ }
+ }
+
+ } else {
+ /* invalid data, this must not happen and indicates error in offboard_mission publisher */
+ mission_state.dataman_id = _offboard_mission.dataman_id;
+ mission_state.count = _offboard_mission.count;
+ mission_state.current_seq = _current_offboard_mission_index;
+
+ warnx("ERROR: invalid mission state");
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: invalid mission state");
+
+ /* write modified state only if changed */
+ if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) {
+ warnx("ERROR: can't save mission state");
+ mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: can't save mission state");
+ }
+ }
+
+ /* unlock MISSION_STATE item */
+ dm_unlock(DM_KEY_MISSION_STATE);
+}
+
+void
+Mission::report_mission_item_reached()
+{
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
+ _mission_result.reached = true;
+ _mission_result.seq_reached = _current_offboard_mission_index;
+ }
+ publish_mission_result();
+}
+
+void
+Mission::report_current_offboard_mission_item()
+{
+ warnx("current offboard mission index: %d", _current_offboard_mission_index);
+ _mission_result.seq_current = _current_offboard_mission_index;
+ publish_mission_result();
+
+ save_offboard_mission_state();
+}
+
+void
+Mission::report_mission_finished()
+{
+ _mission_result.finished = true;
+ publish_mission_result();
+}
+
+void
+Mission::publish_mission_result()
+{
+ /* lazily publish the mission result only once available */
+ if (_mission_result_pub > 0) {
+ /* publish mission result */
+ orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
+
+ } else {
+ /* advertise and publish */
+ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
+ }
+ /* reset reached bool */
+ _mission_result.reached = false;
+ _mission_result.finished = false;
+}
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
new file mode 100644
index 000000000..4da6a1155
--- /dev/null
+++ b/src/modules/navigator/mission.h
@@ -0,0 +1,163 @@
+/****************************************************************************
+ *
+ * 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 mission.h
+ *
+ * Navigator mode to access missions
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_MISSION_H
+#define NAVIGATOR_MISSION_H
+
+#include <drivers/drv_hrt.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <dataman/dataman.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission_result.h>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+#include "mission_feasibility_checker.h"
+
+class Navigator;
+
+class Mission : public MissionBlock
+{
+public:
+ Mission(Navigator *navigator, const char *name);
+
+ virtual ~Mission();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /**
+ * Update onboard mission topic
+ */
+ void update_onboard_mission();
+
+ /**
+ * Update offboard mission topic
+ */
+ void update_offboard_mission();
+
+ /**
+ * Move on to next mission item or switch to loiter
+ */
+ void advance_mission();
+
+ /**
+ * Check distance to first waypoint (with lat/lon)
+ * @return true only if it's not too far from home (< MIS_DIST_1WP)
+ */
+ bool check_dist_1wp();
+
+ /**
+ * Set new mission items
+ */
+ void set_mission_items();
+
+ /**
+ * Read current or next mission item from the dataman and watch out for DO_JUMPS
+ * @return true if successful
+ */
+ bool read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item);
+
+ /**
+ * Save current offboard mission state to dataman
+ */
+ void save_offboard_mission_state();
+
+ /**
+ * Report that a mission item has been reached
+ */
+ void report_mission_item_reached();
+
+ /**
+ * Rport the current mission item
+ */
+ void report_current_offboard_mission_item();
+
+ /**
+ * Report that the mission is finished if one exists or that none exists
+ */
+ void report_mission_finished();
+
+ /**
+ * Publish the mission result so commander and mavlink know what is going on
+ */
+ void publish_mission_result();
+
+ control::BlockParamInt _param_onboard_enabled;
+ control::BlockParamFloat _param_takeoff_alt;
+ control::BlockParamFloat _param_dist_1wp;
+
+ struct mission_s _onboard_mission;
+ struct mission_s _offboard_mission;
+
+ int _current_onboard_mission_index;
+ int _current_offboard_mission_index;
+ bool _need_takeoff;
+ bool _takeoff;
+
+ orb_advert_t _mission_result_pub;
+ struct mission_result_s _mission_result;
+
+ enum {
+ MISSION_TYPE_NONE,
+ MISSION_TYPE_ONBOARD,
+ MISSION_TYPE_OFFBOARD
+ } _mission_type;
+
+ bool _inited;
+ bool _dist_1wp_ok;
+
+ MissionFeasibilityChecker missionFeasiblityChecker; /**< class that checks if a mission is feasible */
+};
+
+#endif
diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp
new file mode 100644
index 000000000..4adf77dce
--- /dev/null
+++ b/src/modules/navigator/mission_block.cpp
@@ -0,0 +1,251 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mission_block.cpp
+ *
+ * Helper class to use mission items
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <sys/types.h>
+#include <string.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <math.h>
+#include <float.h>
+
+#include <systemlib/err.h>
+#include <geo/geo.h>
+#include <mavlink/mavlink_log.h>
+
+#include <uORB/uORB.h>
+
+#include "navigator.h"
+#include "mission_block.h"
+
+
+MissionBlock::MissionBlock(Navigator *navigator, const char *name) :
+ NavigatorMode(navigator, name),
+ _mission_item({0}),
+ _waypoint_position_reached(false),
+ _waypoint_yaw_reached(false),
+ _time_first_inside_orbit(0)
+{
+}
+
+MissionBlock::~MissionBlock()
+{
+}
+
+bool
+MissionBlock::is_mission_item_reached()
+{
+ if (_mission_item.nav_cmd == NAV_CMD_IDLE) {
+ return false;
+ }
+
+ if (_mission_item.nav_cmd == NAV_CMD_LAND) {
+ return _navigator->get_vstatus()->condition_landed;
+ }
+
+ /* TODO: count turns */
+ if ((/*_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||*/
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED)) {
+ return false;
+ }
+
+ hrt_abstime now = hrt_absolute_time();
+
+ if (!_waypoint_position_reached) {
+ float dist = -1.0f;
+ float dist_xy = -1.0f;
+ float dist_z = -1.0f;
+
+ float altitude_amsl = _mission_item.altitude_is_relative
+ ? _mission_item.altitude + _navigator->get_home_position()->alt
+ : _mission_item.altitude;
+
+ dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, altitude_amsl,
+ _navigator->get_global_position()->lat,
+ _navigator->get_global_position()->lon,
+ _navigator->get_global_position()->alt,
+ &dist_xy, &dist_z);
+
+ if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF && _navigator->get_vstatus()->is_rotary_wing) {
+ /* require only altitude for takeoff for multicopter */
+ if (_navigator->get_global_position()->alt >
+ altitude_amsl - _navigator->get_acceptance_radius()) {
+ _waypoint_position_reached = true;
+ }
+ } else if (_mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
+ /* for takeoff mission items use the parameter for the takeoff acceptance radius */
+ if (dist >= 0.0f && dist <= _navigator->get_acceptance_radius()) {
+ _waypoint_position_reached = true;
+ }
+ } else {
+ /* for normal mission items used their acceptance radius */
+ if (dist >= 0.0f && dist <= _mission_item.acceptance_radius) {
+ _waypoint_position_reached = true;
+ }
+ }
+ }
+
+ if (_waypoint_position_reached && !_waypoint_yaw_reached) {
+
+ /* TODO: removed takeoff, why? */
+ if (_navigator->get_vstatus()->is_rotary_wing && isfinite(_mission_item.yaw)) {
+
+ /* check yaw if defined only for rotary wing except takeoff */
+ float yaw_err = _wrap_pi(_mission_item.yaw - _navigator->get_global_position()->yaw);
+
+ if (fabsf(yaw_err) < 0.2f) { /* TODO: get rid of magic number */
+ _waypoint_yaw_reached = true;
+ }
+
+ } else {
+ _waypoint_yaw_reached = true;
+ }
+ }
+
+ /* check if the current waypoint was reached */
+ if (_waypoint_position_reached && _waypoint_yaw_reached) {
+
+ if (_time_first_inside_orbit == 0) {
+ _time_first_inside_orbit = now;
+
+ // if (_mission_item.time_inside > 0.01f) {
+ // mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs",
+ // (double)_mission_item.time_inside);
+ // }
+ }
+
+ /* check if the MAV was long enough inside the waypoint orbit */
+ if (now - _time_first_inside_orbit >= (hrt_abstime)_mission_item.time_inside * 1e6f) {
+ return true;
+ }
+ }
+ return false;
+}
+
+void
+MissionBlock::reset_mission_item_reached()
+{
+ _waypoint_position_reached = false;
+ _waypoint_yaw_reached = false;
+ _time_first_inside_orbit = 0;
+}
+
+void
+MissionBlock::mission_item_to_position_setpoint(const struct mission_item_s *item, struct position_setpoint_s *sp)
+{
+ sp->valid = true;
+ sp->lat = item->lat;
+ sp->lon = item->lon;
+ sp->alt = item->altitude_is_relative ? item->altitude + _navigator->get_home_position()->alt : item->altitude;
+ sp->yaw = item->yaw;
+ sp->loiter_radius = item->loiter_radius;
+ sp->loiter_direction = item->loiter_direction;
+ sp->pitch_min = item->pitch_min;
+
+ switch (item->nav_cmd) {
+ case NAV_CMD_IDLE:
+ sp->type = SETPOINT_TYPE_IDLE;
+ break;
+
+ case NAV_CMD_TAKEOFF:
+ sp->type = SETPOINT_TYPE_TAKEOFF;
+ break;
+
+ case NAV_CMD_LAND:
+ sp->type = SETPOINT_TYPE_LAND;
+ break;
+
+ case NAV_CMD_LOITER_TIME_LIMIT:
+ case NAV_CMD_LOITER_TURN_COUNT:
+ case NAV_CMD_LOITER_UNLIMITED:
+ sp->type = SETPOINT_TYPE_LOITER;
+ break;
+
+ default:
+ sp->type = SETPOINT_TYPE_POSITION;
+ break;
+ }
+}
+
+void
+MissionBlock::set_previous_pos_setpoint()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ if (pos_sp_triplet->current.valid) {
+ memcpy(&pos_sp_triplet->previous, &pos_sp_triplet->current, sizeof(struct position_setpoint_s));
+ }
+}
+
+void
+MissionBlock::set_loiter_item(struct mission_item_s *item)
+{
+ if (_navigator->get_vstatus()->condition_landed) {
+ /* landed, don't takeoff, but switch to IDLE mode */
+ item->nav_cmd = NAV_CMD_IDLE;
+
+ } else {
+ item->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ if (_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid) {
+ /* use current position setpoint */
+ item->lat = pos_sp_triplet->current.lat;
+ item->lon = pos_sp_triplet->current.lon;
+ item->altitude = pos_sp_triplet->current.alt;
+
+ } else {
+ /* use current position */
+ item->lat = _navigator->get_global_position()->lat;
+ item->lon = _navigator->get_global_position()->lon;
+ item->altitude = _navigator->get_global_position()->alt;
+ }
+
+ item->altitude_is_relative = false;
+ item->yaw = NAN;
+ item->loiter_radius = _navigator->get_loiter_radius();
+ item->loiter_direction = 1;
+ item->acceptance_radius = _navigator->get_acceptance_radius();
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0f;
+ item->autocontinue = false;
+ item->origin = ORIGIN_ONBOARD;
+ }
+}
diff --git a/src/modules/navigator/navigator_mission.h b/src/modules/navigator/mission_block.h
index b0f88e016..adf50bc39 100644
--- a/src/modules/navigator/navigator_mission.h
+++ b/src/modules/navigator/mission_block.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -31,75 +31,72 @@
*
****************************************************************************/
/**
- * @file navigator_mission.h
- * Helper class to access missions
+ * @file mission_block.h
*
- * @author Julian Oes <joes@student.ethz.ch>
+ * Helper class to use mission items
+ *
+ * @author Julian Oes <julian@oes.ch>
*/
-#ifndef NAVIGATOR_MISSION_H
-#define NAVIGATOR_MISSION_H
+#ifndef NAVIGATOR_MISSION_BLOCK_H
+#define NAVIGATOR_MISSION_BLOCK_H
+
+#include <drivers/drv_hrt.h>
#include <uORB/topics/mission.h>
-#include <uORB/topics/mission_result.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "navigator_mode.h"
+class Navigator;
-class __EXPORT Mission
+class MissionBlock : public NavigatorMode
{
public:
/**
* Constructor
*/
- Mission();
+ MissionBlock(Navigator *navigator, const char *name);
/**
- * Destructor, also kills the sensors task.
+ * Destructor
*/
- ~Mission();
-
- void set_offboard_dataman_id(int new_id);
- void set_current_offboard_mission_index(int new_index);
- void set_current_onboard_mission_index(int new_index);
- void set_offboard_mission_count(unsigned new_count);
- void set_onboard_mission_count(unsigned new_count);
-
- void set_onboard_mission_allowed(bool allowed);
-
- bool current_mission_available();
- bool next_mission_available();
-
- int get_current_mission_item(struct mission_item_s *mission_item, bool *onboard, unsigned *index);
- int get_next_mission_item(struct mission_item_s *mission_item);
-
- void move_to_next();
-
- void report_mission_item_reached();
- void report_current_offboard_mission_item();
- void publish_mission_result();
+ virtual ~MissionBlock();
-private:
- bool current_onboard_mission_available();
- bool current_offboard_mission_available();
- bool next_onboard_mission_available();
- bool next_offboard_mission_available();
-
- int _offboard_dataman_id;
- unsigned _current_offboard_mission_index;
- unsigned _current_onboard_mission_index;
- unsigned _offboard_mission_item_count; /** number of offboard mission items available */
- unsigned _onboard_mission_item_count; /** number of onboard mission items available */
+protected:
+ /**
+ * Check if mission item has been reached
+ * @return true if successfully reached
+ */
+ bool is_mission_item_reached();
+ /**
+ * Reset all reached flags
+ */
+ void reset_mission_item_reached();
- bool _onboard_mission_allowed;
+ /**
+ * Convert a mission item to a position setpoint
+ *
+ * @param the mission item to convert
+ * @param the position setpoint that needs to be set
+ */
+ void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
- enum {
- MISSION_TYPE_NONE,
- MISSION_TYPE_ONBOARD,
- MISSION_TYPE_OFFBOARD,
- } _current_mission_type;
+ /**
+ * Set previous position setpoint to current setpoint
+ */
+ void set_previous_pos_setpoint();
- int _mission_result_pub;
+ /**
+ * Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position
+ */
+ void set_loiter_item(struct mission_item_s *item);
- struct mission_result_s _mission_result;
+ mission_item_s _mission_item;
+ bool _waypoint_position_reached;
+ bool _waypoint_yaw_reached;
+ hrt_abstime _time_first_inside_orbit;
};
#endif
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
index e1a6854b2..dd7f4c801 100644
--- a/src/modules/navigator/mission_feasibility_checker.cpp
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -215,11 +215,12 @@ bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size
// float slope_alt = wp_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_distance)/_flare_constant) - _H1_virt;
+ return false;
}
void MissionFeasibilityChecker::updateNavigationCapabilities()
{
- int res = orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
+ (void)orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
}
void MissionFeasibilityChecker::init()
diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c
new file mode 100644
index 000000000..881caa24e
--- /dev/null
+++ b/src/modules/navigator/mission_params.c
@@ -0,0 +1,84 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 mission_params.c
+ *
+ * Parameters for mission.
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Mission parameters, accessible via MAVLink
+ */
+
+/**
+ * Take-off altitude
+ *
+ * Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to
+ * MIS_TAKEOFF_ALT on takeoff, then go to waypoint.
+ *
+ * @unit meters
+ * @group Mission
+ */
+PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 10.0f);
+
+/**
+ * Enable persistent onboard mission storage
+ *
+ * When enabled, missions that have been uploaded by the GCS are stored
+ * and reloaded after reboot persistently.
+ *
+ * @min 0
+ * @max 1
+ * @group Mission
+ */
+PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1);
+
+/**
+ * Maximal horizontal distance from home to first waypoint
+ *
+ * Failsafe check to prevent running mission stored from previous flight at a new takeoff location.
+ * Set a value of zero or less to disable. The mission will not be started if the current
+ * waypoint is more distant than MIS_DIS_1WP from the current position.
+ *
+ * @min 0
+ * @max 250
+ * @group Mission
+ */
+PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 175);
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 6ea9dec2b..637eaae59 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+# Copyright (c) 2013-2014 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -39,7 +39,14 @@ MODULE_COMMAND = navigator
SRCS = navigator_main.cpp \
navigator_params.c \
- navigator_mission.cpp \
+ navigator_mode.cpp \
+ mission_block.cpp \
+ mission.cpp \
+ mission_params.c \
+ loiter.cpp \
+ rtl.cpp \
+ rtl_params.c \
+ offboard.cpp \
mission_feasibility_checker.cpp \
geofence.cpp \
geofence_params.c
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
new file mode 100644
index 000000000..bf6e2ea0e
--- /dev/null
+++ b/src/modules/navigator/navigator.h
@@ -0,0 +1,226 @@
+/***************************************************************************
+ *
+ * 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 navigator.h
+ * Helper class to access missions
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef NAVIGATOR_H
+#define NAVIGATOR_H
+
+#include <systemlib/perf_counter.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/vehicle_control_mode.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+#include <uORB/topics/vehicle_global_position.h>
+#include <uORB/topics/parameter_update.h>
+
+#include "navigator_mode.h"
+#include "mission.h"
+#include "loiter.h"
+#include "rtl.h"
+#include "offboard.h"
+#include "geofence.h"
+
+/**
+ * Number of navigation modes that need on_active/on_inactive calls
+ * Currently: mission, loiter, and rtl
+ */
+#define NAVIGATOR_MODE_ARRAY_SIZE 4
+
+class Navigator : public control::SuperBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ Navigator();
+
+ /**
+ * Destructor, also kills the navigators task.
+ */
+ ~Navigator();
+
+ /**
+ * Start the navigator task.
+ *
+ * @return OK on success.
+ */
+ int start();
+
+ /**
+ * Display the navigator status.
+ */
+ void status();
+
+ /**
+ * Add point to geofence
+ */
+ void add_fence_point(int argc, char *argv[]);
+
+ /**
+ * Load fence from file
+ */
+ void load_fence_from_file(const char *filename);
+
+ /**
+ * Setters
+ */
+ void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; }
+ void set_position_setpoint_triplet_updated() { _pos_sp_triplet_updated = true; }
+
+ /**
+ * Getters
+ */
+ struct vehicle_status_s* get_vstatus() { return &_vstatus; }
+ struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; }
+ struct vehicle_global_position_s* get_global_position() { return &_global_pos; }
+ struct home_position_s* get_home_position() { return &_home_pos; }
+ struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
+ int get_onboard_mission_sub() { return _onboard_mission_sub; }
+ int get_offboard_mission_sub() { return _offboard_mission_sub; }
+ int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; }
+ Geofence& get_geofence() { return _geofence; }
+ bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
+ float get_loiter_radius() { return _param_loiter_radius.get(); }
+ float get_acceptance_radius() { return _param_acceptance_radius.get(); }
+ int get_mavlink_fd() { return _mavlink_fd; }
+
+private:
+
+ bool _task_should_exit; /**< if true, sensor task should exit */
+ int _navigator_task; /**< task handle for sensor task */
+
+ int _mavlink_fd; /**< the file descriptor to send messages over mavlink */
+
+ int _global_pos_sub; /**< global position subscription */
+ int _home_pos_sub; /**< home position subscription */
+ int _vstatus_sub; /**< vehicle status subscription */
+ int _capabilities_sub; /**< notification of vehicle capabilities updates */
+ int _offboard_control_sp_sub; /*** offboard control subscription */
+ int _control_mode_sub; /**< vehicle control mode subscription */
+ int _onboard_mission_sub; /**< onboard mission subscription */
+ int _offboard_mission_sub; /**< offboard mission subscription */
+ int _param_update_sub; /**< param update subscription */
+
+ orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
+
+ vehicle_status_s _vstatus; /**< vehicle status */
+ vehicle_control_mode_s _control_mode; /**< vehicle control mode */
+ vehicle_global_position_s _global_pos; /**< global vehicle position */
+ home_position_s _home_pos; /**< home position for RTL */
+ mission_item_s _mission_item; /**< current mission item */
+ navigation_capabilities_s _nav_caps; /**< navigation capabilities */
+ position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
+
+ bool _mission_item_valid; /**< flags if the current mission item is valid */
+
+ perf_counter_t _loop_perf; /**< loop performance counter */
+
+ Geofence _geofence; /**< class that handles the geofence */
+ bool _geofence_violation_warning_sent; /**< prevents spaming to mavlink */
+
+ bool _fence_valid; /**< flag if fence is valid */
+ bool _inside_fence; /**< vehicle is inside fence */
+
+ NavigatorMode *_navigation_mode; /**< abstract pointer to current navigation mode class */
+ Mission _mission; /**< class that handles the missions */
+ Loiter _loiter; /**< class that handles loiter */
+ RTL _rtl; /**< class that handles RTL */
+ Offboard _offboard; /**< class that handles offboard */
+
+ NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
+
+ bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */
+ bool _pos_sp_triplet_updated; /**< flags if position SP triplet needs to be published */
+
+ control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
+ control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
+ /**
+ * Retrieve global position
+ */
+ void global_position_update();
+
+ /**
+ * Retrieve home position
+ */
+ void home_position_update();
+
+ /**
+ * Retreive navigation capabilities
+ */
+ void navigation_capabilities_update();
+
+ /**
+ * Retrieve vehicle status
+ */
+ void vehicle_status_update();
+
+ /**
+ * Retrieve vehicle control mode
+ */
+ void vehicle_control_mode_update();
+
+ /**
+ * Update parameters
+ */
+ void params_update();
+
+ /**
+ * Shim for calling task_main from task_create.
+ */
+ static void task_main_trampoline(int argc, char *argv[]);
+
+ /**
+ * Main task.
+ */
+ void task_main();
+
+ /**
+ * Translate mission item to a position setpoint.
+ */
+ void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
+
+ /**
+ * Publish a new position setpoint triplet for position controllers
+ */
+ void publish_position_setpoint_triplet();
+};
+#endif
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 06e0c5904..1a5ba4c1a 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -32,18 +32,18 @@
****************************************************************************/
/**
* @file navigator_main.cpp
- * Implementation of the main navigation state machine.
*
- * Handles missions, geo fencing and failsafe navigation behavior.
- * Published the mission item triplet for the position controller.
+ * Handles mission items, geo fencing and failsafe navigation behavior.
+ * Published the position setpoint triplet for the position controller.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
* @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
* @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <nuttx/config.h>
+
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -54,42 +54,29 @@
#include <poll.h>
#include <time.h>
#include <sys/ioctl.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+
#include <drivers/device/device.h>
#include <drivers/drv_hrt.h>
#include <arch/board/board.h>
+
#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/home_position.h>
-#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/parameter_update.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/fence.h>
#include <uORB/topics/navigation_capabilities.h>
-#include <systemlib/param/param.h>
+#include <uORB/topics/offboard_control_setpoint.h>
+
#include <systemlib/err.h>
-#include <systemlib/state_table.h>
-#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
#include <geo/geo.h>
-#include <mathlib/mathlib.h>
#include <dataman/dataman.h>
+#include <mathlib/mathlib.h>
#include <mavlink/mavlink_log.h>
-#include <sys/types.h>
-#include <sys/stat.h>
-
-#include "navigator_state.h"
-#include "navigator_mission.h"
-#include "mission_feasibility_checker.h"
-#include "geofence.h"
-
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
+#include "navigator.h"
/**
* navigator app start / stop handling function
@@ -98,342 +85,55 @@ static const int ERROR = -1;
*/
extern "C" __EXPORT int navigator_main(int argc, char *argv[]);
-class Navigator : public StateTable
-{
-public:
- /**
- * Constructor
- */
- Navigator();
-
- /**
- * Destructor, also kills the navigators task.
- */
- ~Navigator();
-
- /**
- * Start the navigator task.
- *
- * @return OK on success.
- */
- int start();
-
- /**
- * Display the navigator status.
- */
- void status();
-
- /**
- * Add point to geofence
- */
- void add_fence_point(int argc, char *argv[]);
-
- /**
- * Load fence from file
- */
- void load_fence_from_file(const char *filename);
-
-private:
-
- bool _task_should_exit; /**< if true, sensor task should exit */
- int _navigator_task; /**< task handle for sensor task */
-
- int _mavlink_fd;
-
- int _global_pos_sub; /**< global position subscription */
- int _home_pos_sub; /**< home position subscription */
- int _vstatus_sub; /**< vehicle status subscription */
- int _params_sub; /**< notification of parameter updates */
- int _offboard_mission_sub; /**< notification of offboard mission updates */
- int _onboard_mission_sub; /**< notification of onboard mission updates */
- int _capabilities_sub; /**< notification of vehicle capabilities updates */
- int _control_mode_sub; /**< vehicle control mode subscription */
-
- orb_advert_t _pos_sp_triplet_pub; /**< publish position setpoint triplet */
- orb_advert_t _mission_result_pub; /**< publish mission result topic */
-
- struct vehicle_status_s _vstatus; /**< vehicle status */
- struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */
- struct vehicle_global_position_s _global_pos; /**< global vehicle position */
- struct home_position_s _home_pos; /**< home position for RTL */
- struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of position setpoints */
- struct mission_result_s _mission_result; /**< mission result for commander/mavlink */
- struct mission_item_s _mission_item; /**< current mission item */
-
- perf_counter_t _loop_perf; /**< loop performance counter */
-
- Geofence _geofence;
- bool _geofence_violation_warning_sent;
-
- bool _fence_valid; /**< flag if fence is valid */
- bool _inside_fence; /**< vehicle is inside fence */
-
- struct navigation_capabilities_s _nav_caps;
-
- class Mission _mission;
-
- bool _mission_item_valid; /**< current mission item valid */
- bool _global_pos_valid; /**< track changes of global_position */
- bool _reset_loiter_pos; /**< if true then loiter position should be set to current position */
- bool _waypoint_position_reached;
- bool _waypoint_yaw_reached;
- uint64_t _time_first_inside_orbit;
- bool _need_takeoff; /**< if need to perform vertical takeoff before going to waypoint (only for MISSION mode and VTOL vehicles) */
- bool _do_takeoff; /**< vertical takeoff state, current mission item is generated by navigator (only for MISSION mode and VTOL vehicles) */
-
- MissionFeasibilityChecker missionFeasiblityChecker;
-
- uint64_t _set_nav_state_timestamp; /**< timestamp of last handled navigation state request */
-
- bool _pos_sp_triplet_updated;
-
- const char *nav_states_str[NAV_STATE_MAX];
-
- struct {
- float min_altitude;
- float acceptance_radius;
- float loiter_radius;
- int onboard_mission_enabled;
- float takeoff_alt;
- float land_alt;
- float rtl_alt;
- float rtl_land_delay;
- } _parameters; /**< local copies of parameters */
-
- struct {
- param_t min_altitude;
- param_t acceptance_radius;
- param_t loiter_radius;
- param_t onboard_mission_enabled;
- param_t takeoff_alt;
- param_t land_alt;
- param_t rtl_alt;
- param_t rtl_land_delay;
- } _parameter_handles; /**< handles for parameters */
-
- enum Event {
- EVENT_NONE_REQUESTED,
- EVENT_READY_REQUESTED,
- EVENT_LOITER_REQUESTED,
- EVENT_MISSION_REQUESTED,
- EVENT_RTL_REQUESTED,
- EVENT_LAND_REQUESTED,
- EVENT_MISSION_CHANGED,
- EVENT_HOME_POSITION_CHANGED,
- MAX_EVENT
- };
-
- /**
- * State machine transition table
- */
- static StateTable::Tran const myTable[NAV_STATE_MAX][MAX_EVENT];
-
- enum RTLState {
- RTL_STATE_NONE = 0,
- RTL_STATE_CLIMB,
- RTL_STATE_RETURN,
- RTL_STATE_DESCEND
- };
-
- enum RTLState _rtl_state;
-
- /**
- * Update our local parameter cache.
- */
- void parameters_update();
-
- /**
- * Retrieve global position
- */
- void global_position_update();
-
- /**
- * Retrieve home position
- */
- void home_position_update();
-
- /**
- * Retreive navigation capabilities
- */
- void navigation_capabilities_update();
-
- /**
- * Retrieve offboard mission.
- */
- void offboard_mission_update(bool isrotaryWing);
-
- /**
- * Retrieve onboard mission.
- */
- void onboard_mission_update();
-
- /**
- * Retrieve vehicle status
- */
- void vehicle_status_update();
-
- /**
- * Retrieve vehicle control mode
- */
- void vehicle_control_mode_update();
-
- /**
- * Shim for calling task_main from task_create.
- */
- static void task_main_trampoline(int argc, char *argv[]);
-
- /**
- * Main task.
- */
- void task_main();
-
- void publish_safepoints(unsigned points);
-
- /**
- * Functions that are triggered when a new state is entered.
- */
- void start_none();
- void start_ready();
- void start_loiter();
- void start_mission();
- void start_rtl();
- void start_land();
- void start_land_home();
-
- /**
- * Fork for state transitions
- */
- void request_loiter_or_ready();
- void request_mission_if_available();
-
- /**
- * Guards offboard mission
- */
- bool offboard_mission_available(unsigned relative_index);
-
- /**
- * Guards onboard mission
- */
- bool onboard_mission_available(unsigned relative_index);
-
- /**
- * Reset all "reached" flags.
- */
- void reset_reached();
-
- /**
- * Check if current mission item has been reached.
- */
- bool check_mission_item_reached();
-
- /**
- * Perform actions when current mission item reached.
- */
- void on_mission_item_reached();
-
- /**
- * Move to next waypoint
- */
- void set_mission_item();
-
- /**
- * Switch to next RTL state
- */
- void set_rtl_item();
-
- /**
- * Set position setpoint for mission item
- */
- void position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item);
-
- /**
- * Helper function to get a takeoff item
- */
- void get_takeoff_setpoint(position_setpoint_s *pos_sp);
-
- /**
- * Publish a new mission item triplet for position controller
- */
- void publish_position_setpoint_triplet();
-};
namespace navigator
{
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
-
Navigator *g_navigator;
}
Navigator::Navigator() :
-
-/* state machine transition table */
- StateTable(&myTable[0][0], NAV_STATE_MAX, MAX_EVENT),
-
+ SuperBlock(NULL, "NAV"),
_task_should_exit(false),
_navigator_task(-1),
_mavlink_fd(-1),
-
-/* subscriptions */
_global_pos_sub(-1),
_home_pos_sub(-1),
_vstatus_sub(-1),
- _params_sub(-1),
- _offboard_mission_sub(-1),
- _onboard_mission_sub(-1),
_capabilities_sub(-1),
+ _offboard_control_sp_sub(-1),
_control_mode_sub(-1),
-
-/* publications */
+ _onboard_mission_sub(-1),
+ _offboard_mission_sub(-1),
_pos_sp_triplet_pub(-1),
-
-/* performance counters */
+ _vstatus({}),
+ _control_mode({}),
+ _global_pos({}),
+ _home_pos({}),
+ _mission_item({}),
+ _nav_caps({}),
+ _pos_sp_triplet({}),
+ _mission_item_valid(false),
_loop_perf(perf_alloc(PC_ELAPSED, "navigator")),
-
+ _geofence({}),
_geofence_violation_warning_sent(false),
_fence_valid(false),
_inside_fence(true),
- _mission(),
- _mission_item_valid(false),
- _global_pos_valid(false),
- _reset_loiter_pos(true),
- _waypoint_position_reached(false),
- _waypoint_yaw_reached(false),
- _time_first_inside_orbit(0),
- _need_takeoff(true),
- _do_takeoff(false),
- _set_nav_state_timestamp(0),
- _pos_sp_triplet_updated(false),
-/* states */
- _rtl_state(RTL_STATE_NONE)
+ _navigation_mode(nullptr),
+ _mission(this, "MIS"),
+ _loiter(this, "LOI"),
+ _rtl(this, "RTL"),
+ _offboard(this, "OFF"),
+ _param_loiter_radius(this, "LOITER_RAD"),
+ _param_acceptance_radius(this, "ACC_RAD")
{
- _parameter_handles.min_altitude = param_find("NAV_MIN_ALT");
- _parameter_handles.acceptance_radius = param_find("NAV_ACCEPT_RAD");
- _parameter_handles.loiter_radius = param_find("NAV_LOITER_RAD");
- _parameter_handles.onboard_mission_enabled = param_find("NAV_ONB_MIS_EN");
- _parameter_handles.takeoff_alt = param_find("NAV_TAKEOFF_ALT");
- _parameter_handles.land_alt = param_find("NAV_LAND_ALT");
- _parameter_handles.rtl_alt = param_find("NAV_RTL_ALT");
- _parameter_handles.rtl_land_delay = param_find("NAV_RTL_LAND_T");
-
- memset(&_pos_sp_triplet, 0, sizeof(struct position_setpoint_triplet_s));
- memset(&_mission_item, 0, sizeof(struct mission_item_s));
-
- memset(&nav_states_str, 0, sizeof(nav_states_str));
- nav_states_str[0] = "NONE";
- nav_states_str[1] = "READY";
- nav_states_str[2] = "LOITER";
- nav_states_str[3] = "MISSION";
- nav_states_str[4] = "RTL";
- nav_states_str[5] = "LAND";
-
- /* Initialize state machine */
- myState = NAV_STATE_NONE;
- start_none();
+ /* Create a list of our possible navigation types */
+ _navigation_mode_array[0] = &_mission;
+ _navigation_mode_array[1] = &_loiter;
+ _navigation_mode_array[2] = &_rtl;
+ _navigation_mode_array[3] = &_offboard;
+
+ updateParams();
}
Navigator::~Navigator()
@@ -462,27 +162,6 @@ Navigator::~Navigator()
}
void
-Navigator::parameters_update()
-{
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), _params_sub, &update);
-
- param_get(_parameter_handles.min_altitude, &(_parameters.min_altitude));
- param_get(_parameter_handles.acceptance_radius, &(_parameters.acceptance_radius));
- param_get(_parameter_handles.loiter_radius, &(_parameters.loiter_radius));
- param_get(_parameter_handles.onboard_mission_enabled, &(_parameters.onboard_mission_enabled));
- param_get(_parameter_handles.takeoff_alt, &(_parameters.takeoff_alt));
- param_get(_parameter_handles.land_alt, &(_parameters.land_alt));
- param_get(_parameter_handles.rtl_alt, &(_parameters.rtl_alt));
- param_get(_parameter_handles.rtl_land_delay, &(_parameters.rtl_land_delay));
-
- _mission.set_onboard_mission_allowed((bool)_parameter_handles.onboard_mission_enabled);
-
- _geofence.updateParams();
-}
-
-void
Navigator::global_position_update()
{
orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
@@ -500,56 +179,6 @@ Navigator::navigation_capabilities_update()
orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps);
}
-
-void
-Navigator::offboard_mission_update(bool isrotaryWing)
-{
- struct mission_s offboard_mission;
-
- if (orb_copy(ORB_ID(offboard_mission), _offboard_mission_sub, &offboard_mission) == OK) {
-
- /* Check mission feasibility, for now do not handle the return value,
- * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */
- dm_item_t dm_current;
-
- if (offboard_mission.dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
-
- } else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
- }
-
- missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence, _home_pos.alt);
-
- _mission.set_offboard_dataman_id(offboard_mission.dataman_id);
-
- _mission.set_offboard_mission_count(offboard_mission.count);
- _mission.set_current_offboard_mission_index(offboard_mission.current_index);
-
- } else {
- _mission.set_offboard_mission_count(0);
- _mission.set_current_offboard_mission_index(0);
- }
-
- _mission.publish_mission_result();
-}
-
-void
-Navigator::onboard_mission_update()
-{
- struct mission_s onboard_mission;
-
- if (orb_copy(ORB_ID(onboard_mission), _onboard_mission_sub, &onboard_mission) == OK) {
-
- _mission.set_onboard_mission_count(onboard_mission.count);
- _mission.set_current_onboard_mission_index(onboard_mission.current_index);
-
- } else {
- _mission.set_onboard_mission_count(0);
- _mission.set_current_onboard_mission_index(0);
- }
-}
-
void
Navigator::vehicle_status_update()
{
@@ -570,6 +199,13 @@ Navigator::vehicle_control_mode_update()
}
void
+Navigator::params_update()
+{
+ parameter_update_s param_update;
+ orb_copy(ORB_ID(parameter_update), _param_update_sub, &param_update);
+}
+
+void
Navigator::task_main_trampoline(int argc, char *argv[])
{
navigator::g_navigator->task_main();
@@ -580,16 +216,12 @@ Navigator::task_main()
{
/* inform about start */
warnx("Initializing..");
- fflush(stdout);
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
- mavlink_log_info(_mavlink_fd, "[navigator] started");
-
/* Try to load the geofence:
* if /fs/microsd/etc/geofence.txt load from this file
- * else clear geofence data in datamanager
- */
+ * else clear geofence data in datamanager */
struct stat buffer;
if (stat(GEOFENCE_FILENAME, &buffer) == 0) {
@@ -603,68 +235,59 @@ Navigator::task_main()
warnx("Could not clear geofence");
}
- /*
- * do subscriptions
- */
+ /* do subscriptions */
_global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
- _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
_capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- _params_sub = orb_subscribe(ORB_ID(parameter_update));
_home_pos_sub = orb_subscribe(ORB_ID(home_position));
+ _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
+ _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
+ _param_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ _offboard_control_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
/* copy all topics first time */
vehicle_status_update();
vehicle_control_mode_update();
- parameters_update();
global_position_update();
home_position_update();
navigation_capabilities_update();
- offboard_mission_update(_vstatus.is_rotary_wing);
- onboard_mission_update();
+ params_update();
/* rate limit position updates to 50 Hz */
orb_set_interval(_global_pos_sub, 20);
- unsigned prevState = NAV_STATE_NONE;
hrt_abstime mavlink_open_time = 0;
const hrt_abstime mavlink_open_interval = 500000;
/* wakeup source(s) */
- struct pollfd fds[8];
+ struct pollfd fds[6];
/* Setup of loop */
- fds[0].fd = _params_sub;
+ fds[0].fd = _global_pos_sub;
fds[0].events = POLLIN;
- fds[1].fd = _global_pos_sub;
+ fds[1].fd = _home_pos_sub;
fds[1].events = POLLIN;
- fds[2].fd = _home_pos_sub;
+ fds[2].fd = _capabilities_sub;
fds[2].events = POLLIN;
- fds[3].fd = _capabilities_sub;
+ fds[3].fd = _vstatus_sub;
fds[3].events = POLLIN;
- fds[4].fd = _offboard_mission_sub;
+ fds[4].fd = _control_mode_sub;
fds[4].events = POLLIN;
- fds[5].fd = _onboard_mission_sub;
+ fds[5].fd = _param_update_sub;
fds[5].events = POLLIN;
- fds[6].fd = _vstatus_sub;
- fds[6].events = POLLIN;
- fds[7].fd = _control_mode_sub;
- fds[7].events = POLLIN;
while (!_task_should_exit) {
/* wait for up to 100ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
- /* timed out - periodic check for _task_should_exit, etc. */
if (pret == 0) {
+ /* timed out - periodic check for _task_should_exit, etc. */
continue;
- }
- /* this is undesirable but not much we can do - might want to flag unhappy status */
- if (pret < 0) {
+ } else if (pret < 0) {
+ /* this is undesirable but not much we can do - might want to flag unhappy status */
warn("poll error %d, %d", pret, errno);
continue;
}
@@ -677,162 +300,103 @@ Navigator::task_main()
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
}
+ /* parameters updated */
+ if (fds[5].revents & POLLIN) {
+ params_update();
+ updateParams();
+ }
+
/* vehicle control mode updated */
- if (fds[7].revents & POLLIN) {
+ if (fds[4].revents & POLLIN) {
vehicle_control_mode_update();
}
/* vehicle status updated */
- if (fds[6].revents & POLLIN) {
+ if (fds[3].revents & POLLIN) {
vehicle_status_update();
-
- /* evaluate state requested by commander */
- if (_control_mode.flag_armed && _control_mode.flag_control_auto_enabled) {
- /* publish position setpoint triplet on each status update if navigator active */
- _pos_sp_triplet_updated = true;
-
- if (_vstatus.set_nav_state_timestamp != _set_nav_state_timestamp) {
- /* commander requested new navigation mode, try to set it */
- switch (_vstatus.set_nav_state) {
- case NAV_STATE_NONE:
- /* nothing to do */
- break;
-
- case NAV_STATE_LOITER:
- request_loiter_or_ready();
- break;
-
- case NAV_STATE_MISSION:
- request_mission_if_available();
- break;
-
- case NAV_STATE_RTL:
- if (!(_rtl_state == RTL_STATE_DESCEND &&
- (myState == NAV_STATE_LAND || myState == NAV_STATE_LOITER)) &&
- _vstatus.condition_home_position_valid) {
- dispatch(EVENT_RTL_REQUESTED);
- }
-
- break;
-
- case NAV_STATE_LAND:
- dispatch(EVENT_LAND_REQUESTED);
-
- break;
-
- default:
- warnx("ERROR: Requested navigation state not supported");
- break;
- }
-
- } else {
- /* on first switch to AUTO try mission by default, if none is available fallback to loiter */
- if (myState == NAV_STATE_NONE) {
- request_mission_if_available();
- }
- }
-
- /* check if waypoint has been reached in MISSION, RTL and LAND modes */
- if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL || myState == NAV_STATE_LAND) {
- if (check_mission_item_reached()) {
- on_mission_item_reached();
- }
- }
-
- } else {
- /* navigator shouldn't act */
- dispatch(EVENT_NONE_REQUESTED);
- }
-
- _set_nav_state_timestamp = _vstatus.set_nav_state_timestamp;
- }
-
- /* parameters updated */
- if (fds[0].revents & POLLIN) {
- parameters_update();
- /* note that these new parameters won't be in effect until a mission triplet is published again */
}
/* navigation capabilities updated */
- if (fds[3].revents & POLLIN) {
+ if (fds[2].revents & POLLIN) {
navigation_capabilities_update();
}
- /* offboard mission updated */
- if (fds[4].revents & POLLIN) {
- offboard_mission_update(_vstatus.is_rotary_wing);
- // XXX check if mission really changed
- dispatch(EVENT_MISSION_CHANGED);
- }
-
- /* onboard mission updated */
- if (fds[5].revents & POLLIN) {
- onboard_mission_update();
- // XXX check if mission really changed
- dispatch(EVENT_MISSION_CHANGED);
- }
-
/* home position updated */
- if (fds[2].revents & POLLIN) {
+ if (fds[1].revents & POLLIN) {
home_position_update();
- // XXX check if home position really changed
- dispatch(EVENT_HOME_POSITION_CHANGED);
}
/* global position updated */
- if (fds[1].revents & POLLIN) {
+ if (fds[0].revents & POLLIN) {
global_position_update();
- if (_control_mode.flag_armed && _control_mode.flag_control_auto_enabled) {
- /* publish position setpoint triplet on each position update if navigator active */
- _pos_sp_triplet_updated = true;
-
- if (myState == NAV_STATE_LAND && !_global_pos_valid) {
- /* got global position when landing, update setpoint */
- start_land();
- }
-
- /* check if waypoint has been reached in MISSION, RTL and LAND modes */
- if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL || myState == NAV_STATE_LAND) {
- if (check_mission_item_reached()) {
- on_mission_item_reached();
- }
- }
- }
-
/* Check geofence violation */
if (!_geofence.inside(&_global_pos)) {
- //xxx: publish geofence violation here (or change local flag depending on which app handles the flight termination)
/* Issue a warning about the geofence violation once */
if (!_geofence_violation_warning_sent) {
mavlink_log_critical(_mavlink_fd, "#audio: Geofence violation");
_geofence_violation_warning_sent = true;
}
-
} else {
/* Reset the _geofence_violation_warning_sent field */
_geofence_violation_warning_sent = false;
}
}
- _global_pos_valid = _vstatus.condition_global_position_valid;
+ /* Do stuff according to navigation state set by commander */
+ switch (_vstatus.nav_state) {
+ case NAVIGATION_STATE_MANUAL:
+ case NAVIGATION_STATE_ACRO:
+ case NAVIGATION_STATE_ALTCTL:
+ case NAVIGATION_STATE_POSCTL:
+ _navigation_mode = nullptr;
+ _can_loiter_at_sp = false;
+ break;
+ case NAVIGATION_STATE_AUTO_MISSION:
+ _navigation_mode = &_mission;
+ break;
+ case NAVIGATION_STATE_AUTO_LOITER:
+ _navigation_mode = &_loiter;
+ break;
+ case NAVIGATION_STATE_AUTO_RTL:
+ _navigation_mode = &_rtl;
+ break;
+ case NAVIGATION_STATE_AUTO_RTGS:
+ _navigation_mode = &_rtl; /* TODO: change this to something else */
+ break;
+ case NAVIGATION_STATE_LAND:
+ case NAVIGATION_STATE_TERMINATION:
+ case NAVIGATION_STATE_OFFBOARD:
+ _navigation_mode = &_offboard;
+ break;
+ default:
+ _navigation_mode = nullptr;
+ _can_loiter_at_sp = false;
+ break;
+ }
- /* publish position setpoint triplet if updated */
- if (_pos_sp_triplet_updated) {
- _pos_sp_triplet_updated = false;
- publish_position_setpoint_triplet();
+ /* iterate through navigation modes and set active/inactive for each */
+ for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
+ _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);
}
- /* notify user about state changes */
- if (myState != prevState) {
- mavlink_log_info(_mavlink_fd, "#audio: navigation state: %s", nav_states_str[myState]);
- prevState = myState;
+ /* if nothing is running, set position setpoint triplet invalid */
+ if (_navigation_mode == nullptr) {
+ // TODO publish empty sp only once
+ _pos_sp_triplet.previous.valid = false;
+ _pos_sp_triplet.current.valid = false;
+ _pos_sp_triplet.next.valid = false;
+ _pos_sp_triplet_updated = true;
+ }
+
+ if (_pos_sp_triplet_updated) {
+ publish_position_setpoint_triplet();
+ _pos_sp_triplet_updated = false;
}
perf_end(_loop_perf);
}
-
warnx("exiting.");
_navigator_task = -1;
@@ -863,19 +427,21 @@ Navigator::start()
void
Navigator::status()
{
- warnx("Global position: %svalid", _global_pos_valid ? "" : "in");
-
- if (_global_pos_valid) {
- warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon, _global_pos.lat);
- warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
- (double)_global_pos.alt, (double)(_global_pos.alt - _home_pos.alt));
- warnx("Ground velocity in m/s, N %5.5f, E %5.5f, D %5.5f",
- (double)_global_pos.vel_n, (double)_global_pos.vel_e, (double)_global_pos.vel_d);
- warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
- }
+ /* TODO: add this again */
+ // warnx("Global position is %svalid", _global_pos_valid ? "" : "in");
+
+ // if (_global_pos.global_valid) {
+ // warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon, _global_pos.lat);
+ // warnx("Altitude %5.5f meters, altitude above home %5.5f meters",
+ // (double)_global_pos.alt, (double)(_global_pos.alt - _home_pos.alt));
+ // warnx("Ground velocity in m/s, N %5.5f, E %5.5f, D %5.5f",
+ // (double)_global_pos.vel_n, (double)_global_pos.vel_e, (double)_global_pos.vel_d);
+ // warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F));
+ // }
if (_fence_valid) {
warnx("Geofence is valid");
+ /* TODO: needed? */
// warnx("Vertex longitude latitude");
// for (unsigned i = 0; i < _fence.count; i++)
// warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat);
@@ -883,747 +449,19 @@ Navigator::status()
} else {
warnx("Geofence not set");
}
-
- switch (myState) {
- case NAV_STATE_NONE:
- warnx("State: None");
- break;
-
- case NAV_STATE_LOITER:
- warnx("State: Loiter");
- break;
-
- case NAV_STATE_MISSION:
- warnx("State: Mission");
- break;
-
- case NAV_STATE_RTL:
- warnx("State: RTL");
- break;
-
- default:
- warnx("State: Unknown");
- break;
- }
-}
-
-StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = {
- {
- /* NAV_STATE_NONE */
- /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
- /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
- /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
- /* EVENT_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
- /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
- /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE},
- },
- {
- /* NAV_STATE_READY */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
- /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
- /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
- /* EVENT_LAND_REQUESTED */ {NO_ACTION, NAV_STATE_READY},
- /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
- /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY},
- },
- {
- /* NAV_STATE_LOITER */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
- /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER},
- /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
- /* EVENT_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
- /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
- /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER},
- },
- {
- /* NAV_STATE_MISSION */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
- /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
- /* EVENT_MISSION_REQUESTED */ {NO_ACTION, NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
- /* EVENT_LAND_REQUESTED */ {ACTION(&Navigator::start_land), NAV_STATE_LAND},
- /* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION},
- },
- {
- /* NAV_STATE_RTL */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
- /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
- /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {NO_ACTION, NAV_STATE_RTL},
- /* EVENT_LAND_REQUESTED */ {ACTION(&Navigator::start_land_home), NAV_STATE_LAND},
- /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_RTL},
- /* EVENT_HOME_POSITION_CHANGED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL}, // TODO need to reset rtl_state
- },
- {
- /* NAV_STATE_LAND */
- /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE},
- /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY},
- /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER},
- /* EVENT_MISSION_REQUESTED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION},
- /* EVENT_RTL_REQUESTED */ {ACTION(&Navigator::start_rtl), NAV_STATE_RTL},
- /* EVENT_LAND_REQUESTED */ {NO_ACTION, NAV_STATE_LAND},
- /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
- /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LAND},
- },
-};
-
-void
-Navigator::start_none()
-{
- reset_reached();
-
- _pos_sp_triplet.previous.valid = false;
- _pos_sp_triplet.current.valid = false;
- _pos_sp_triplet.next.valid = false;
- _mission_item_valid = false;
-
- _reset_loiter_pos = true;
- _do_takeoff = false;
- _rtl_state = RTL_STATE_NONE;
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::start_ready()
-{
- reset_reached();
-
- _pos_sp_triplet.previous.valid = false;
- _pos_sp_triplet.current.valid = true;
- _pos_sp_triplet.next.valid = false;
-
- _pos_sp_triplet.current.type = SETPOINT_TYPE_IDLE;
-
- _mission_item_valid = false;
-
- _reset_loiter_pos = true;
- _do_takeoff = false;
-
- if (_rtl_state != RTL_STATE_DESCEND) {
- /* reset RTL state if landed not at home */
- _rtl_state = RTL_STATE_NONE;
- }
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::start_loiter()
-{
- reset_reached();
-
- _do_takeoff = false;
-
- /* set loiter position if needed */
- if (_reset_loiter_pos || !_pos_sp_triplet.current.valid) {
- _reset_loiter_pos = false;
-
- _pos_sp_triplet.current.lat = _global_pos.lat;
- _pos_sp_triplet.current.lon = _global_pos.lon;
- _pos_sp_triplet.current.yaw = NAN; // NAN means to use current yaw
-
- float min_alt_amsl = _parameters.min_altitude + _home_pos.alt;
-
- /* use current altitude if above min altitude set by parameter */
- if (_global_pos.alt < min_alt_amsl && !_vstatus.is_rotary_wing) {
- _pos_sp_triplet.current.alt = min_alt_amsl;
- mavlink_log_info(_mavlink_fd, "#audio: loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt));
-
- } else {
- _pos_sp_triplet.current.alt = _global_pos.alt;
- mavlink_log_info(_mavlink_fd, "#audio: loiter at current altitude");
- }
-
- }
- _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER;
- _pos_sp_triplet.current.loiter_radius = _parameters.loiter_radius;
- _pos_sp_triplet.current.loiter_direction = 1;
- _pos_sp_triplet.previous.valid = false;
- _pos_sp_triplet.current.valid = true;
- _pos_sp_triplet.next.valid = false;
- _mission_item_valid = false;
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::start_mission()
-{
- _need_takeoff = true;
-
- set_mission_item();
-}
-
-void
-Navigator::set_mission_item()
-{
- reset_reached();
-
- /* copy current mission to previous item */
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- _reset_loiter_pos = true;
- _do_takeoff = false;
-
- int ret;
- bool onboard;
- unsigned index;
-
- ret = _mission.get_current_mission_item(&_mission_item, &onboard, &index);
-
- if (ret == OK) {
- _mission.report_current_offboard_mission_item();
-
- _mission_item_valid = true;
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- if (_mission_item.nav_cmd != NAV_CMD_RETURN_TO_LAUNCH &&
- _mission_item.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT &&
- _mission_item.nav_cmd != NAV_CMD_LOITER_TURN_COUNT &&
- _mission_item.nav_cmd != NAV_CMD_LOITER_UNLIMITED) {
- /* don't reset RTL state on RTL or LOITER items */
- _rtl_state = RTL_STATE_NONE;
- }
-
- if (_vstatus.is_rotary_wing) {
- if (_need_takeoff && (
- _mission_item.nav_cmd == NAV_CMD_TAKEOFF ||
- _mission_item.nav_cmd == NAV_CMD_WAYPOINT ||
- _mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH ||
- _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED
- )) {
- /* do special TAKEOFF handling for VTOL */
- _need_takeoff = false;
-
- /* calculate desired takeoff altitude AMSL */
- float takeoff_alt_amsl = _pos_sp_triplet.current.alt;
-
- if (_vstatus.condition_landed) {
- /* takeoff to at least NAV_TAKEOFF_ALT from ground if landed */
- takeoff_alt_amsl = fmaxf(takeoff_alt_amsl, _global_pos.alt + _parameters.takeoff_alt);
- }
-
- /* check if we really need takeoff */
- if (_vstatus.condition_landed || _global_pos.alt < takeoff_alt_amsl - _mission_item.acceptance_radius) {
- /* force TAKEOFF if landed or waypoint altitude is more than current */
- _do_takeoff = true;
-
- /* move current position setpoint to next */
- memcpy(&_pos_sp_triplet.next, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- /* set current setpoint to takeoff */
-
- _pos_sp_triplet.current.lat = _global_pos.lat;
- _pos_sp_triplet.current.lon = _global_pos.lon;
- _pos_sp_triplet.current.alt = takeoff_alt_amsl;
- _pos_sp_triplet.current.yaw = NAN;
- _pos_sp_triplet.current.type = SETPOINT_TYPE_TAKEOFF;
- }
-
- } else if (_mission_item.nav_cmd == NAV_CMD_LAND) {
- /* will need takeoff after landing */
- _need_takeoff = true;
- }
- }
-
- if (_do_takeoff) {
- mavlink_log_info(_mavlink_fd, "#audio: takeoff to %.1fm above home", (double)(_pos_sp_triplet.current.alt - _home_pos.alt));
-
- } else {
- if (onboard) {
- mavlink_log_info(_mavlink_fd, "#audio: heading to onboard WP %d", index);
-
- } else {
- mavlink_log_info(_mavlink_fd, "#audio: heading to offboard WP %d", index);
- }
- }
-
- } else {
- /* since a mission is not advanced without WPs available, this is not supposed to happen */
- _mission_item_valid = false;
- _pos_sp_triplet.current.valid = false;
- warnx("ERROR: current WP can't be set");
- }
-
- if (!_do_takeoff) {
- mission_item_s item_next;
- ret = _mission.get_next_mission_item(&item_next);
-
- if (ret == OK) {
- position_setpoint_from_mission_item(&_pos_sp_triplet.next, &item_next);
-
- } else {
- /* this will fail for the last WP */
- _pos_sp_triplet.next.valid = false;
- }
- }
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::start_rtl()
-{
- _do_takeoff = false;
-
- /* decide if we need climb */
- if (_rtl_state == RTL_STATE_NONE) {
- if (_global_pos.alt < _home_pos.alt + _parameters.rtl_alt) {
- _rtl_state = RTL_STATE_CLIMB;
-
- } else {
- _rtl_state = RTL_STATE_RETURN;
- }
- }
-
- /* if switching directly to return state, reset altitude setpoint */
- if (_rtl_state == RTL_STATE_RETURN) {
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = _global_pos.alt;
- }
-
- _reset_loiter_pos = true;
- set_rtl_item();
-}
-
-void
-Navigator::start_land()
-{
- reset_reached();
-
- /* this state can be requested by commander even if no global position available,
- * in his case controller must perform landing without position control */
- _do_takeoff = false;
- _reset_loiter_pos = true;
-
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- _mission_item_valid = true;
-
- _mission_item.lat = _global_pos.lat;
- _mission_item.lon = _global_pos.lon;
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = _global_pos.alt;
- _mission_item.yaw = NAN;
- _mission_item.loiter_radius = _parameters.loiter_radius;
- _mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_LAND;
- _mission_item.acceptance_radius = _parameters.acceptance_radius;
- _mission_item.time_inside = 0.0f;
- _mission_item.pitch_min = 0.0f;
- _mission_item.autocontinue = true;
- _mission_item.origin = ORIGIN_ONBOARD;
-
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- _pos_sp_triplet.next.valid = false;
-}
-
-void
-Navigator::start_land_home()
-{
- reset_reached();
-
- /* land to home position, should be called when hovering above home, from RTL state */
- _do_takeoff = false;
- _reset_loiter_pos = true;
-
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- _mission_item_valid = true;
-
- _mission_item.lat = _home_pos.lat;
- _mission_item.lon = _home_pos.lon;
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = _home_pos.alt;
- _mission_item.yaw = NAN;
- _mission_item.loiter_radius = _parameters.loiter_radius;
- _mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_LAND;
- _mission_item.acceptance_radius = _parameters.acceptance_radius;
- _mission_item.time_inside = 0.0f;
- _mission_item.pitch_min = 0.0f;
- _mission_item.autocontinue = true;
- _mission_item.origin = ORIGIN_ONBOARD;
-
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- _pos_sp_triplet.next.valid = false;
-}
-
-void
-Navigator::set_rtl_item()
-{
- reset_reached();
-
- switch (_rtl_state) {
- case RTL_STATE_CLIMB: {
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- float climb_alt = _home_pos.alt + _parameters.rtl_alt;
-
- if (_vstatus.condition_landed) {
- climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt);
- }
-
- _mission_item_valid = true;
-
- _mission_item.lat = _global_pos.lat;
- _mission_item.lon = _global_pos.lon;
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = climb_alt;
- _mission_item.yaw = NAN;
- _mission_item.loiter_radius = _parameters.loiter_radius;
- _mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
- _mission_item.acceptance_radius = _parameters.acceptance_radius;
- _mission_item.time_inside = 0.0f;
- _mission_item.pitch_min = 0.0f;
- _mission_item.autocontinue = true;
- _mission_item.origin = ORIGIN_ONBOARD;
-
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- _pos_sp_triplet.next.valid = false;
-
- mavlink_log_info(_mavlink_fd, "#audio: RTL: climb to %.1fm above home", (double)(climb_alt - _home_pos.alt));
- break;
- }
-
- case RTL_STATE_RETURN: {
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- _mission_item_valid = true;
-
- _mission_item.lat = _home_pos.lat;
- _mission_item.lon = _home_pos.lon;
- // don't change altitude
- if (_pos_sp_triplet.previous.valid) {
- /* if previous setpoint is valid then use it to calculate heading to home */
- _mission_item.yaw = get_bearing_to_next_waypoint(_pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon, _mission_item.lat, _mission_item.lon);
-
- } else {
- /* else use current position */
- _mission_item.yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, _mission_item.lat, _mission_item.lon);
- }
- _mission_item.loiter_radius = _parameters.loiter_radius;
- _mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
- _mission_item.acceptance_radius = _parameters.acceptance_radius;
- _mission_item.time_inside = 0.0f;
- _mission_item.pitch_min = 0.0f;
- _mission_item.autocontinue = true;
- _mission_item.origin = ORIGIN_ONBOARD;
-
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- _pos_sp_triplet.next.valid = false;
-
- mavlink_log_info(_mavlink_fd, "#audio: RTL: return at %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt));
- break;
- }
-
- case RTL_STATE_DESCEND: {
- memcpy(&_pos_sp_triplet.previous, &_pos_sp_triplet.current, sizeof(position_setpoint_s));
-
- _mission_item_valid = true;
-
- _mission_item.lat = _home_pos.lat;
- _mission_item.lon = _home_pos.lon;
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = _home_pos.alt + _parameters.land_alt;
- _mission_item.yaw = NAN;
- _mission_item.loiter_radius = _parameters.loiter_radius;
- _mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
- _mission_item.acceptance_radius = _parameters.acceptance_radius;
- _mission_item.time_inside = _parameters.rtl_land_delay < 0.0f ? 0.0f : _parameters.rtl_land_delay;
- _mission_item.pitch_min = 0.0f;
- _mission_item.autocontinue = _parameters.rtl_land_delay > -0.001f;
- _mission_item.origin = ORIGIN_ONBOARD;
-
- position_setpoint_from_mission_item(&_pos_sp_triplet.current, &_mission_item);
-
- _pos_sp_triplet.next.valid = false;
-
- mavlink_log_info(_mavlink_fd, "#audio: RTL: descend to %.1fm above home", (double)(_mission_item.altitude - _home_pos.alt));
- break;
- }
-
- default: {
- mavlink_log_critical(_mavlink_fd, "#audio: [navigator] error: unknown RTL state: %d", _rtl_state);
- start_loiter();
- break;
- }
- }
-
- _pos_sp_triplet_updated = true;
-}
-
-void
-Navigator::request_loiter_or_ready()
-{
- /* XXX workaround: no landing detector for fixedwing yet */
- if (_vstatus.condition_landed && _vstatus.is_rotary_wing) {
- dispatch(EVENT_READY_REQUESTED);
-
- } else {
- dispatch(EVENT_LOITER_REQUESTED);
- }
-}
-
-void
-Navigator::request_mission_if_available()
-{
- if (_mission.current_mission_available()) {
- dispatch(EVENT_MISSION_REQUESTED);
-
- } else {
- request_loiter_or_ready();
- }
-}
-
-void
-Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item)
-{
- sp->valid = true;
-
- if (item->nav_cmd == NAV_CMD_RETURN_TO_LAUNCH) {
- /* set home position for RTL item */
- sp->lat = _home_pos.lat;
- sp->lon = _home_pos.lon;
- sp->alt = _home_pos.alt + _parameters.rtl_alt;
-
- if (_pos_sp_triplet.previous.valid) {
- /* if previous setpoint is valid then use it to calculate heading to home */
- sp->yaw = get_bearing_to_next_waypoint(_pos_sp_triplet.previous.lat, _pos_sp_triplet.previous.lon, sp->lat, sp->lon);
-
- } else {
- /* else use current position */
- sp->yaw = get_bearing_to_next_waypoint(_global_pos.lat, _global_pos.lon, sp->lat, sp->lon);
- }
- sp->loiter_radius = _parameters.loiter_radius;
- sp->loiter_direction = 1;
- sp->pitch_min = 0.0f;
-
- } else {
- sp->lat = item->lat;
- sp->lon = item->lon;
- sp->alt = item->altitude_is_relative ? item->altitude + _home_pos.alt : item->altitude;
- sp->yaw = item->yaw;
- sp->loiter_radius = item->loiter_radius;
- sp->loiter_direction = item->loiter_direction;
- sp->pitch_min = item->pitch_min;
- }
-
- if (item->nav_cmd == NAV_CMD_TAKEOFF) {
- sp->type = SETPOINT_TYPE_TAKEOFF;
-
- } else if (item->nav_cmd == NAV_CMD_LAND) {
- sp->type = SETPOINT_TYPE_LAND;
-
- } else if (item->nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
- item->nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- item->nav_cmd == NAV_CMD_LOITER_UNLIMITED) {
- sp->type = SETPOINT_TYPE_LOITER;
-
- } else {
- sp->type = SETPOINT_TYPE_NORMAL;
- }
-}
-
-bool
-Navigator::check_mission_item_reached()
-{
- /* only check if there is actually a mission item to check */
- if (!_mission_item_valid) {
- return false;
- }
-
- if (_mission_item.nav_cmd == NAV_CMD_LAND) {
- return _vstatus.condition_landed;
- }
-
- /* XXX TODO count turns */
- if ((_mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
- _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED) &&
- _mission_item.loiter_radius > 0.01f) {
-
- return false;
- }
-
- uint64_t now = hrt_absolute_time();
-
- if (!_waypoint_position_reached) {
- float acceptance_radius;
-
- if (_mission_item.nav_cmd == NAV_CMD_WAYPOINT && _mission_item.acceptance_radius > 0.01f) {
- acceptance_radius = _mission_item.acceptance_radius;
-
- } else {
- acceptance_radius = _parameters.acceptance_radius;
- }
-
- if (_do_takeoff) {
- /* require only altitude for takeoff */
- if (_global_pos.alt > _pos_sp_triplet.current.alt - acceptance_radius) {
- _waypoint_position_reached = true;
- }
-
- } else {
- float dist = -1.0f;
- float dist_xy = -1.0f;
- float dist_z = -1.0f;
-
- /* calculate AMSL altitude for this waypoint */
- float wp_alt_amsl = _mission_item.altitude;
-
- if (_mission_item.altitude_is_relative)
- wp_alt_amsl += _home_pos.alt;
-
- dist = get_distance_to_point_global_wgs84(_mission_item.lat, _mission_item.lon, wp_alt_amsl,
- (double)_global_pos.lat, (double)_global_pos.lon, _global_pos.alt,
- &dist_xy, &dist_z);
-
- if (dist >= 0.0f && dist <= acceptance_radius) {
- _waypoint_position_reached = true;
- }
- }
- }
-
- if (_waypoint_position_reached && !_waypoint_yaw_reached) {
- if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item.yaw)) {
- /* check yaw if defined only for rotary wing except takeoff */
- float yaw_err = _wrap_pi(_mission_item.yaw - _global_pos.yaw);
-
- if (fabsf(yaw_err) < 0.2f) { /* XXX get rid of magic number */
- _waypoint_yaw_reached = true;
- }
-
- } else {
- _waypoint_yaw_reached = true;
- }
- }
-
- /* check if the current waypoint was reached */
- if (_waypoint_position_reached && _waypoint_yaw_reached) {
- if (_time_first_inside_orbit == 0) {
- _time_first_inside_orbit = now;
-
- if (_mission_item.time_inside > 0.01f) {
- mavlink_log_info(_mavlink_fd, "#audio: waypoint reached, wait for %.1fs", (double)_mission_item.time_inside);
- }
- }
-
- /* check if the MAV was long enough inside the waypoint orbit */
- if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item.time_inside * 1e6)
- || _mission_item.nav_cmd == NAV_CMD_TAKEOFF) {
- reset_reached();
- return true;
- }
- }
-
- return false;
-
-}
-
-void
-Navigator::reset_reached()
-{
- _time_first_inside_orbit = 0;
- _waypoint_position_reached = false;
- _waypoint_yaw_reached = false;
-
-}
-
-void
-Navigator::on_mission_item_reached()
-{
- if (myState == NAV_STATE_MISSION) {
-
- _mission.report_mission_item_reached();
-
- if (_do_takeoff) {
- /* takeoff completed */
- _do_takeoff = false;
- mavlink_log_info(_mavlink_fd, "#audio: takeoff completed");
-
- } else {
- /* advance by one mission item */
- _mission.move_to_next();
- }
-
- if (_mission.current_mission_available()) {
- if (_mission_item.autocontinue) {
- /* continue mission */
- set_mission_item();
-
- } else {
- /* autocontinue disabled for this item */
- request_loiter_or_ready();
- }
-
- } else {
- /* if no more mission items available then finish mission */
- /* loiter at last waypoint */
- _reset_loiter_pos = false;
- mavlink_log_info(_mavlink_fd, "[navigator] mission completed");
- request_loiter_or_ready();
- }
-
- } else if (myState == NAV_STATE_RTL) {
- /* RTL completed */
- if (_rtl_state == RTL_STATE_DESCEND) {
- /* hovering above home position, land if needed or loiter */
- mavlink_log_info(_mavlink_fd, "[navigator] RTL completed");
-
- if (_mission_item.autocontinue) {
- dispatch(EVENT_LAND_REQUESTED);
-
- } else {
- _reset_loiter_pos = false;
- dispatch(EVENT_LOITER_REQUESTED);
- }
-
- } else {
- /* next RTL step */
- _rtl_state = (RTLState)(_rtl_state + 1);
- set_rtl_item();
- }
-
- } else if (myState == NAV_STATE_LAND) {
- /* landing completed */
- mavlink_log_info(_mavlink_fd, "[navigator] landing completed");
- dispatch(EVENT_READY_REQUESTED);
- }
- _mission.publish_mission_result();
}
void
Navigator::publish_position_setpoint_triplet()
{
/* update navigation state */
- _pos_sp_triplet.nav_state = static_cast<nav_state_t>(myState);
+ /* TODO: set nav_state */
/* lazily publish the position setpoint triplet only once available */
if (_pos_sp_triplet_pub > 0) {
- /* publish the position setpoint triplet */
orb_publish(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_pub, &_pos_sp_triplet);
} else {
- /* advertise and publish */
_pos_sp_triplet_pub = orb_advertise(ORB_ID(position_setpoint_triplet), &_pos_sp_triplet);
}
}
diff --git a/src/modules/navigator/navigator_mission.cpp b/src/modules/navigator/navigator_mission.cpp
deleted file mode 100644
index 49fc62785..000000000
--- a/src/modules/navigator/navigator_mission.cpp
+++ /dev/null
@@ -1,319 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-/**
- * @file navigator_mission.cpp
- * Helper class to access missions
- *
- * @author Julian Oes <joes@student.ethz.ch>
- */
-
-#include <string.h>
-#include <stdlib.h>
-#include <dataman/dataman.h>
-#include <systemlib/err.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/mission_result.h>
-#include "navigator_mission.h"
-
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-static const int ERROR = -1;
-
-
-Mission::Mission() :
-
- _offboard_dataman_id(-1),
- _current_offboard_mission_index(0),
- _current_onboard_mission_index(0),
- _offboard_mission_item_count(0),
- _onboard_mission_item_count(0),
- _onboard_mission_allowed(false),
- _current_mission_type(MISSION_TYPE_NONE),
- _mission_result_pub(-1)
-{
- memset(&_mission_result, 0, sizeof(struct mission_result_s));
-}
-
-Mission::~Mission()
-{
-
-}
-
-void
-Mission::set_offboard_dataman_id(int new_id)
-{
- _offboard_dataman_id = new_id;
-}
-
-void
-Mission::set_current_offboard_mission_index(int new_index)
-{
- if (new_index != -1) {
- warnx("specifically set to %d", new_index);
- _current_offboard_mission_index = (unsigned)new_index;
- } else {
-
- /* if less WPs available, reset to first WP */
- if (_current_offboard_mission_index >= _offboard_mission_item_count) {
- _current_offboard_mission_index = 0;
- }
- }
- report_current_offboard_mission_item();
-}
-
-void
-Mission::set_current_onboard_mission_index(int new_index)
-{
- if (new_index != -1) {
- _current_onboard_mission_index = (unsigned)new_index;
- } else {
-
- /* if less WPs available, reset to first WP */
- if (_current_onboard_mission_index >= _onboard_mission_item_count) {
- _current_onboard_mission_index = 0;
- }
- }
- // TODO: implement this for onboard missions as well
- // report_current_mission_item();
-}
-
-void
-Mission::set_offboard_mission_count(unsigned new_count)
-{
- _offboard_mission_item_count = new_count;
-}
-
-void
-Mission::set_onboard_mission_count(unsigned new_count)
-{
- _onboard_mission_item_count = new_count;
-}
-
-void
-Mission::set_onboard_mission_allowed(bool allowed)
-{
- _onboard_mission_allowed = allowed;
-}
-
-bool
-Mission::current_mission_available()
-{
- return (current_onboard_mission_available() || current_offboard_mission_available());
-
-}
-
-bool
-Mission::next_mission_available()
-{
- return (next_onboard_mission_available() || next_offboard_mission_available());
-}
-
-int
-Mission::get_current_mission_item(struct mission_item_s *new_mission_item, bool *onboard, unsigned *index)
-{
- /* try onboard mission first */
- if (current_onboard_mission_available()) {
-
- const ssize_t len = sizeof(struct mission_item_s);
-
- if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index, new_mission_item, len) != len) {
- /* not supposed to happen unless the datamanager can't access the SD card, etc. */
- return ERROR;
- }
-
- _current_mission_type = MISSION_TYPE_ONBOARD;
- *onboard = true;
- *index = _current_onboard_mission_index;
-
- /* otherwise fallback to offboard */
-
- } else if (current_offboard_mission_available()) {
-
- dm_item_t dm_current;
-
- if (_offboard_dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
-
- } else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
- }
-
- const ssize_t len = sizeof(struct mission_item_s);
-
- if (dm_read(dm_current, _current_offboard_mission_index, new_mission_item, len) != len) {
- /* not supposed to happen unless the datamanager can't access the SD card, etc. */
- _current_mission_type = MISSION_TYPE_NONE;
- return ERROR;
- }
-
- _current_mission_type = MISSION_TYPE_OFFBOARD;
- *onboard = false;
- *index = _current_offboard_mission_index;
-
- } else {
- /* happens when no more mission items can be added as a next item */
- _current_mission_type = MISSION_TYPE_NONE;
- return ERROR;
- }
-
- return OK;
-}
-
-int
-Mission::get_next_mission_item(struct mission_item_s *new_mission_item)
-{
- /* try onboard mission first */
- if (next_onboard_mission_available()) {
-
- const ssize_t len = sizeof(struct mission_item_s);
-
- if (dm_read(DM_KEY_WAYPOINTS_ONBOARD, _current_onboard_mission_index + 1, new_mission_item, len) != len) {
- /* not supposed to happen unless the datamanager can't access the SD card, etc. */
- return ERROR;
- }
-
- /* otherwise fallback to offboard */
-
- } else if (next_offboard_mission_available()) {
-
- dm_item_t dm_current;
-
- if (_offboard_dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
-
- } else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
- }
-
- const ssize_t len = sizeof(struct mission_item_s);
-
- if (dm_read(dm_current, _current_offboard_mission_index + 1, new_mission_item, len) != len) {
- /* not supposed to happen unless the datamanager can't access the SD card, etc. */
- return ERROR;
- }
-
- } else {
- /* happens when no more mission items can be added as a next item */
- return ERROR;
- }
-
- return OK;
-}
-
-
-bool
-Mission::current_onboard_mission_available()
-{
- return _onboard_mission_item_count > _current_onboard_mission_index && _onboard_mission_allowed;
-}
-
-bool
-Mission::current_offboard_mission_available()
-{
- return _offboard_mission_item_count > _current_offboard_mission_index;
-}
-
-bool
-Mission::next_onboard_mission_available()
-{
- unsigned next = 0;
-
- if (_current_mission_type != MISSION_TYPE_ONBOARD) {
- next = 1;
- }
-
- return _onboard_mission_item_count > (_current_onboard_mission_index + next) && _onboard_mission_allowed;
-}
-
-bool
-Mission::next_offboard_mission_available()
-{
- unsigned next = 0;
-
- if (_current_mission_type != MISSION_TYPE_OFFBOARD) {
- next = 1;
- }
-
- return _offboard_mission_item_count > (_current_offboard_mission_index + next);
-}
-
-void
-Mission::move_to_next()
-{
- switch (_current_mission_type) {
- case MISSION_TYPE_ONBOARD:
- _current_onboard_mission_index++;
- break;
-
- case MISSION_TYPE_OFFBOARD:
- _current_offboard_mission_index++;
- break;
-
- case MISSION_TYPE_NONE:
- default:
- break;
- }
-}
-
-void
-Mission::report_mission_item_reached()
-{
- if (_current_mission_type == MISSION_TYPE_OFFBOARD) {
- _mission_result.mission_reached = true;
- _mission_result.mission_index_reached = _current_offboard_mission_index;
- }
-}
-
-void
-Mission::report_current_offboard_mission_item()
-{
- _mission_result.index_current_mission = _current_offboard_mission_index;
-}
-
-void
-Mission::publish_mission_result()
-{
- /* lazily publish the mission result only once available */
- if (_mission_result_pub > 0) {
- /* publish mission result */
- orb_publish(ORB_ID(mission_result), _mission_result_pub, &_mission_result);
-
- } else {
- /* advertise and publish */
- _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result);
- }
- /* reset reached bool */
- _mission_result.mission_reached = false;
-}
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
new file mode 100644
index 000000000..f43215665
--- /dev/null
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -0,0 +1,95 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 navigator_mode.cpp
+ *
+ * Base class for different modes in navigator
+ *
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include "navigator_mode.h"
+#include "navigator.h"
+
+NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) :
+ SuperBlock(NULL, name),
+ _navigator(navigator),
+ _first_run(true)
+{
+ /* load initial params */
+ updateParams();
+ /* set initial mission items */
+ on_inactive();
+}
+
+NavigatorMode::~NavigatorMode()
+{
+}
+
+void
+NavigatorMode::run(bool active) {
+ if (active) {
+ if (_first_run) {
+ /* first run */
+ _first_run = false;
+ on_activation();
+
+ } else {
+ /* periodic updates when active */
+ on_active();
+ }
+
+ } else {
+ /* periodic updates when inactive */
+ _first_run = true;
+ on_inactive();
+ }
+}
+
+void
+NavigatorMode::on_inactive()
+{
+}
+
+void
+NavigatorMode::on_activation()
+{
+ /* invalidate position setpoint by default */
+ _navigator->get_position_setpoint_triplet()->current.valid = false;
+}
+
+void
+NavigatorMode::on_active()
+{
+}
diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h
new file mode 100644
index 000000000..a7ba79bba
--- /dev/null
+++ b/src/modules/navigator/navigator_mode.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 navigator_mode.h
+ *
+ * Base class for different modes in navigator
+ *
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef NAVIGATOR_MODE_H
+#define NAVIGATOR_MODE_H
+
+#include <drivers/drv_hrt.h>
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <dataman/dataman.h>
+
+#include <uORB/topics/position_setpoint_triplet.h>
+
+class Navigator;
+
+class NavigatorMode : public control::SuperBlock
+{
+public:
+ /**
+ * Constructor
+ */
+ NavigatorMode(Navigator *navigator, const char *name);
+
+ /**
+ * Destructor
+ */
+ virtual ~NavigatorMode();
+
+ void run(bool active);
+
+ /**
+ * This function is called while the mode is inactive
+ */
+ virtual void on_inactive();
+
+ /**
+ * This function is called one time when mode become active, poos_sp_triplet must be initialized here
+ */
+ virtual void on_activation();
+
+ /**
+ * This function is called while the mode is active
+ */
+ virtual void on_active();
+
+protected:
+ Navigator *_navigator;
+
+private:
+ bool _first_run;
+};
+
+#endif
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 5139283b6..084afe340 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -17,7 +17,7 @@
* 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
+ * 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,
@@ -34,104 +34,33 @@
/**
* @file navigator_params.c
*
- * Parameters defined by the navigator task.
+ * Parameters for navigator in general
*
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
+ * @author Julian Oes <julian@oes.ch>
*/
#include <nuttx/config.h>
#include <systemlib/param/param.h>
-/*
- * Navigator parameters, accessible via MAVLink
- */
-
-/**
- * Minimum altitude (fixed wing only)
- *
- * Minimum altitude above home for LOITER.
- *
- * @unit meters
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f);
-
-/**
- * Waypoint acceptance radius
- *
- * Default value of acceptance radius (if not specified in mission item).
- *
- * @unit meters
- * @min 0.0
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f);
-
/**
- * Loiter radius (fixed wing only)
+ * Loiter radius (FW only)
*
- * Default value of loiter radius (if not specified in mission item).
+ * Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).
*
* @unit meters
* @min 0.0
- * @group Navigation
+ * @group Mission
*/
PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f);
/**
- * Enable onboard mission
- *
- * @group Navigation
- */
-PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0);
-
-/**
- * Take-off altitude
- *
- * Even if first waypoint has altitude less then NAV_TAKEOFF_ALT above home position, system will climb to NAV_TAKEOFF_ALT on takeoff, then go to waypoint.
- *
- * @unit meters
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f);
-
-/**
- * Landing altitude
- *
- * Stay at this altitude above home position after RTL descending. Land (i.e. slowly descend) from this altitude if autolanding allowed.
- *
- * @unit meters
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f);
-
-/**
- * Return-To-Launch altitude
+ * Acceptance Radius
*
- * Minimum altitude above home position for going home in RTL mode.
+ * Default acceptance radius, overridden by acceptance radius of waypoint if set.
*
* @unit meters
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f);
-
-/**
- * Return-To-Launch delay
- *
- * Delay after descend before landing in RTL mode.
- * If set to -1 the system will not land but loiter at NAV_LAND_ALT.
- *
- * @unit seconds
- * @group Navigation
- */
-PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f);
-
-/**
- * Enable parachute deployment
- *
- * @group Navigation
+ * @min 1.0
+ * @group Mission
*/
-PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0);
+PARAM_DEFINE_FLOAT(NAV_ACC_RAD, 25.0f);
diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp
new file mode 100644
index 000000000..dcb5c6000
--- /dev/null
+++ b/src/modules/navigator/offboard.cpp
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 offboard.cpp
+ *
+ * Helper class for offboard commands
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "navigator.h"
+#include "offboard.h"
+
+Offboard::Offboard(Navigator *navigator, const char *name) :
+ NavigatorMode(navigator, name),
+ _offboard_control_sp({0})
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+Offboard::~Offboard()
+{
+}
+
+void
+Offboard::on_inactive()
+{
+}
+
+void
+Offboard::on_activation()
+{
+}
+
+void
+Offboard::on_active()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ bool updated;
+ orb_check(_navigator->get_offboard_control_sp_sub(), &updated);
+ if (updated) {
+ update_offboard_control_setpoint();
+ }
+
+ /* copy offboard setpoints to the corresponding topics */
+ if (_navigator->get_control_mode()->flag_control_position_enabled
+ && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
+ /* position control */
+ pos_sp_triplet->current.x = _offboard_control_sp.p1;
+ pos_sp_triplet->current.y = _offboard_control_sp.p2;
+ pos_sp_triplet->current.yaw = _offboard_control_sp.p3;
+ pos_sp_triplet->current.z = -_offboard_control_sp.p4;
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.position_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+
+ } else if (_navigator->get_control_mode()->flag_control_velocity_enabled
+ && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) {
+ /* velocity control */
+ pos_sp_triplet->current.vx = _offboard_control_sp.p2;
+ pos_sp_triplet->current.vy = _offboard_control_sp.p1;
+ pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3;
+ pos_sp_triplet->current.vz = _offboard_control_sp.p4;
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.velocity_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+ }
+
+}
+
+
+void
+Offboard::update_offboard_control_setpoint()
+{
+ orb_copy(ORB_ID(offboard_control_setpoint), _navigator->get_offboard_control_sp_sub(), &_offboard_control_sp);
+
+}
diff --git a/src/modules/navigator/offboard.h b/src/modules/navigator/offboard.h
new file mode 100644
index 000000000..66b923bdb
--- /dev/null
+++ b/src/modules/navigator/offboard.h
@@ -0,0 +1,72 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 offboard.h
+ *
+ * Helper class for offboard commands
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_OFFBOARD_H
+#define NAVIGATOR_OFFBOARD_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/offboard_control_setpoint.h>
+
+#include "navigator_mode.h"
+
+class Navigator;
+
+class Offboard : public NavigatorMode
+{
+public:
+ Offboard(Navigator *navigator, const char *name);
+
+ ~Offboard();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+private:
+ void update_offboard_control_setpoint();
+
+ struct offboard_control_setpoint_s _offboard_control_sp;
+};
+
+#endif
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
new file mode 100644
index 000000000..142a73409
--- /dev/null
+++ b/src/modules/navigator/rtl.cpp
@@ -0,0 +1,317 @@
+/****************************************************************************
+ *
+ * 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 navigator_rtl.cpp
+ * Helper class to access RTL
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+#include <geo/geo.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+
+#include "navigator.h"
+#include "rtl.h"
+
+#define DELAY_SIGMA 0.01f
+
+RTL::RTL(Navigator *navigator, const char *name) :
+ MissionBlock(navigator, name),
+ _rtl_state(RTL_STATE_NONE),
+ _param_return_alt(this, "RETURN_ALT"),
+ _param_descend_alt(this, "DESCEND_ALT"),
+ _param_land_delay(this, "LAND_DELAY")
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+RTL::~RTL()
+{
+}
+
+void
+RTL::on_inactive()
+{
+ /* reset RTL state only if setpoint moved */
+ if (!_navigator->get_can_loiter_at_sp()) {
+ _rtl_state = RTL_STATE_NONE;
+ }
+}
+
+void
+RTL::on_activation()
+{
+ /* decide where to enter the RTL procedure when we switch into it */
+ if (_rtl_state == RTL_STATE_NONE) {
+ /* for safety reasons don't go into RTL if landed */
+ if (_navigator->get_vstatus()->condition_landed) {
+ _rtl_state = RTL_STATE_LANDED;
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed");
+
+ /* if lower than return altitude, climb up first */
+ } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt
+ + _param_return_alt.get()) {
+ _rtl_state = RTL_STATE_CLIMB;
+
+ /* otherwise go straight to return */
+ } else {
+ /* set altitude setpoint to current altitude */
+ _rtl_state = RTL_STATE_RETURN;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_global_position()->alt;
+ }
+ }
+
+ set_rtl_item();
+}
+
+void
+RTL::on_active()
+{
+ if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) {
+ advance_rtl();
+ set_rtl_item();
+ }
+}
+
+void
+RTL::set_rtl_item()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* make sure we have the latest params */
+ updateParams();
+
+ set_previous_pos_setpoint();
+ _navigator->set_can_loiter_at_sp(false);
+
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB: {
+ float climb_alt = _navigator->get_home_position()->alt + _param_return_alt.get();
+
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = climb_alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: climb to %d meters above home",
+ (int)(climb_alt - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_RETURN: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ // don't change altitude
+
+ if (pos_sp_triplet->previous.valid) {
+ /* if previous setpoint is valid then use it to calculate heading to home */
+ _mission_item.yaw = get_bearing_to_next_waypoint(
+ pos_sp_triplet->previous.lat, pos_sp_triplet->previous.lon,
+ _mission_item.lat, _mission_item.lon);
+
+ } else {
+ /* else use current position */
+ _mission_item.yaw = get_bearing_to_next_waypoint(
+ _navigator->get_global_position()->lat, _navigator->get_global_position()->lon,
+ _mission_item.lat, _mission_item.lon);
+ }
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_WAYPOINT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: return at %d meters above home",
+ (int)(_mission_item.altitude - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_DESCEND: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt + _param_descend_alt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LOITER_TIME_LIMIT;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = false;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: descend to %d meters above home",
+ (int)(_mission_item.altitude - _navigator->get_home_position()->alt));
+ break;
+ }
+
+ case RTL_STATE_LOITER: {
+ bool autoland = _param_land_delay.get() > -DELAY_SIGMA;
+
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt + _param_descend_alt.get();
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = autoland ? NAV_CMD_LOITER_TIME_LIMIT : NAV_CMD_LOITER_UNLIMITED;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = _param_land_delay.get() < 0.0f ? 0.0f : _param_land_delay.get();
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = autoland;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ _navigator->set_can_loiter_at_sp(true);
+
+ if (autoland) {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: loiter %.1fs", (double)_mission_item.time_inside);
+
+ } else {
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: completed, loiter");
+ }
+ break;
+ }
+
+ case RTL_STATE_LAND: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_LAND;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: land at home");
+ break;
+ }
+
+ case RTL_STATE_LANDED: {
+ _mission_item.lat = _navigator->get_home_position()->lat;
+ _mission_item.lon = _navigator->get_home_position()->lon;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_home_position()->alt;
+ _mission_item.yaw = NAN;
+ _mission_item.loiter_radius = _navigator->get_loiter_radius();
+ _mission_item.loiter_direction = 1;
+ _mission_item.nav_cmd = NAV_CMD_IDLE;
+ _mission_item.acceptance_radius = _navigator->get_acceptance_radius();
+ _mission_item.time_inside = 0.0f;
+ _mission_item.pitch_min = 0.0f;
+ _mission_item.autocontinue = true;
+ _mission_item.origin = ORIGIN_ONBOARD;
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: completed, landed");
+ break;
+ }
+
+ default:
+ break;
+ }
+
+ reset_mission_item_reached();
+
+ /* convert mission item to current position setpoint and make it valid */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+RTL::advance_rtl()
+{
+ switch (_rtl_state) {
+ case RTL_STATE_CLIMB:
+ _rtl_state = RTL_STATE_RETURN;
+ break;
+
+ case RTL_STATE_RETURN:
+ _rtl_state = RTL_STATE_DESCEND;
+ break;
+
+ case RTL_STATE_DESCEND:
+ /* only go to land if autoland is enabled */
+ if (_param_land_delay.get() < -DELAY_SIGMA || _param_land_delay.get() > DELAY_SIGMA) {
+ _rtl_state = RTL_STATE_LOITER;
+
+ } else {
+ _rtl_state = RTL_STATE_LAND;
+ }
+ break;
+
+ case RTL_STATE_LOITER:
+ _rtl_state = RTL_STATE_LAND;
+ break;
+
+ case RTL_STATE_LAND:
+ _rtl_state = RTL_STATE_LANDED;
+ break;
+
+ default:
+ break;
+ }
+}
diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h
new file mode 100644
index 000000000..5928f1f07
--- /dev/null
+++ b/src/modules/navigator/rtl.h
@@ -0,0 +1,96 @@
+/***************************************************************************
+ *
+ * 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 navigator_rtl.h
+ * Helper class for RTL
+ *
+ * @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef NAVIGATOR_RTL_H
+#define NAVIGATOR_RTL_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/topics/mission.h>
+#include <uORB/topics/mission.h>
+#include <uORB/topics/home_position.h>
+#include <uORB/topics/vehicle_global_position.h>
+
+#include "navigator_mode.h"
+#include "mission_block.h"
+
+class Navigator;
+
+class RTL : public MissionBlock
+{
+public:
+ RTL(Navigator *navigator, const char *name);
+
+ ~RTL();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+
+private:
+ /**
+ * Set the RTL item
+ */
+ void set_rtl_item();
+
+ /**
+ * Move to next RTL item
+ */
+ void advance_rtl();
+
+ enum RTLState {
+ RTL_STATE_NONE = 0,
+ RTL_STATE_CLIMB,
+ RTL_STATE_RETURN,
+ RTL_STATE_DESCEND,
+ RTL_STATE_LOITER,
+ RTL_STATE_LAND,
+ RTL_STATE_LANDED,
+ } _rtl_state;
+
+ control::BlockParamFloat _param_return_alt;
+ control::BlockParamFloat _param_descend_alt;
+ control::BlockParamFloat _param_land_delay;
+};
+
+#endif
diff --git a/src/modules/navigator/rtl_params.c b/src/modules/navigator/rtl_params.c
new file mode 100644
index 000000000..bfe6ce7e1
--- /dev/null
+++ b/src/modules/navigator/rtl_params.c
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 rtl_params.c
+ *
+ * Parameters for RTL
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * RTL parameters, accessible via MAVLink
+ */
+
+/**
+ * Loiter radius after RTL (FW only)
+ *
+ * Default value of loiter radius after RTL (fixedwing only).
+ *
+ * @unit meters
+ * @min 0.0
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_LOITER_RAD, 50.0f);
+
+/**
+ * RTL altitude
+ *
+ * Altitude to fly back in RTL in meters
+ *
+ * @unit meters
+ * @min 0
+ * @max 1
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_RETURN_ALT, 100);
+
+
+/**
+ * RTL loiter altitude
+ *
+ * Stay at this altitude above home position after RTL descending.
+ * Land (i.e. slowly descend) from this altitude if autolanding allowed.
+ *
+ * @unit meters
+ * @min 0
+ * @max 100
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_DESCEND_ALT, 20);
+
+/**
+ * RTL delay
+ *
+ * Delay after descend before landing in RTL mode.
+ * If set to -1 the system will not land but loiter at NAV_LAND_ALT.
+ *
+ * @unit seconds
+ * @min -1
+ * @max
+ * @group RTL
+ */
+PARAM_DEFINE_FLOAT(RTL_LAND_DELAY, -1.0f);
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 f908d7a3b..05eae047c 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -49,6 +49,7 @@
#include <sys/prctl.h>
#include <termios.h>
#include <math.h>
+#include <float.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/actuator_controls.h>
@@ -179,15 +180,21 @@ int position_estimator_inav_main(int argc, char *argv[])
exit(1);
}
-void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2], float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
+static void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2], float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
{
FILE *f = fopen("/fs/microsd/inav.log", "a");
if (f) {
char *s = malloc(256);
- unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f] y_est=[%.5f %.5f] z_est=[%.5f %.5f] x_est_prev=[%.5f %.5f] y_est_prev=[%.5f %.5f] z_est_prev=[%.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], y_est[0], y_est[1], z_est[0], z_est[1], x_est_prev[0], x_est_prev[1], y_est_prev[0], y_est_prev[1], z_est_prev[0], z_est_prev[1]);
+ unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f] y_est=[%.5f %.5f] z_est=[%.5f %.5f] x_est_prev=[%.5f %.5f] y_est_prev=[%.5f %.5f] z_est_prev=[%.5f %.5f]\n",
+ hrt_absolute_time(), msg, (double)dt,
+ (double)x_est[0], (double)x_est[1], (double)y_est[0], (double)y_est[1], (double)z_est[0], (double)z_est[1],
+ (double)x_est_prev[0], (double)x_est_prev[1], (double)y_est_prev[0], (double)y_est_prev[1], (double)z_est_prev[0], (double)z_est_prev[1]);
fwrite(s, 1, n, f);
- n = snprintf(s, 256, "\tacc=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", acc[0], acc[1], acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v);
+ n = snprintf(s, 256, "\tacc=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n",
+ (double)acc[0], (double)acc[1], (double)acc[2],
+ (double)corr_gps[0][0], (double)corr_gps[1][0], (double)corr_gps[2][0], (double)corr_gps[0][1], (double)corr_gps[1][1], (double)corr_gps[2][1],
+ (double)w_xy_gps_p, (double)w_xy_gps_v);
fwrite(s, 1, n, f);
free(s);
}
@@ -261,9 +268,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
hrt_abstime t_prev = 0;
- /* acceleration in NED frame */
- float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
-
/* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */
float acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
float acc_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
@@ -285,7 +289,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
hrt_abstime flow_prev = 0; // time of last flow measurement
hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
- hrt_abstime xy_src_time = 0; // time of last available position data
bool gps_valid = false; // GPS is valid
bool sonar_valid = false; // sonar is valid
@@ -370,8 +373,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
} else {
wait_baro = false;
baro_offset /= (float) baro_init_cnt;
- warnx("baro offs: %.2f", baro_offset);
- mavlink_log_info(mavlink_fd, "[inav] baro offs: %.2f", baro_offset);
+ warnx("baro offs: %.2f", (double)baro_offset);
+ mavlink_log_info(mavlink_fd, "[inav] baro offs: %.2f", (double)baro_offset);
local_pos.z_valid = true;
local_pos.v_z_valid = true;
}
@@ -475,7 +478,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
flow_prev = flow.flow_timestamp;
- if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && att.R[2][2] > 0.7 && flow.ground_distance_m != sonar_prev) {
+ if ((flow.ground_distance_m > 0.31f) &&
+ (flow.ground_distance_m < 4.0f) &&
+ (att.R[2][2] > 0.7f) &&
+ (fabsf(flow.ground_distance_m - sonar_prev) > FLT_EPSILON)) {
+
sonar_time = t;
sonar_prev = flow.ground_distance_m;
corr_sonar = flow.ground_distance_m + surface_offset + z_est[0];
@@ -497,7 +504,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
sonar_valid_time = t;
sonar_valid = true;
local_pos.surface_bottom_timestamp = t;
- mavlink_log_info(mavlink_fd, "[inav] new surface level: %.2f", surface_offset);
+ mavlink_log_info(mavlink_fd, "[inav] new surface level: %.2f", (double)surface_offset);
}
} else {
@@ -510,7 +517,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float flow_q = flow.quality / 255.0f;
float dist_bottom = - z_est[0] - surface_offset;
- if (dist_bottom > 0.3f && flow_q > params.flow_q_min && (t < sonar_valid_time + sonar_valid_timeout) && att.R[2][2] > 0.7) {
+ if (dist_bottom > 0.3f && flow_q > params.flow_q_min && (t < sonar_valid_time + sonar_valid_timeout) && att.R[2][2] > 0.7f) {
/* distance to surface */
float flow_dist = dist_bottom / att.R[2][2];
/* check if flow if too large for accurate measurements */
@@ -558,7 +565,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
/* under ideal conditions, on 1m distance assume EPH = 10cm */
- eph_flow = 0.1 / w_flow;
+ eph_flow = 0.1f / w_flow;
flow_valid = true;
@@ -619,13 +626,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* hysteresis for GPS quality */
if (gps_valid) {
- if (gps.eph_m > max_eph_epv || gps.epv_m > max_eph_epv || gps.fix_type < 3) {
+ if (gps.eph > max_eph_epv || gps.epv > max_eph_epv || gps.fix_type < 3) {
gps_valid = false;
mavlink_log_info(mavlink_fd, "[inav] GPS signal lost");
}
} else {
- if (gps.eph_m < max_eph_epv * 0.7f && gps.epv_m < max_eph_epv * 0.7f && gps.fix_type >= 3) {
+ if (gps.eph < max_eph_epv * 0.7f && gps.epv < max_eph_epv * 0.7f && gps.fix_type >= 3) {
gps_valid = true;
reset_est = true;
mavlink_log_info(mavlink_fd, "[inav] GPS signal found");
@@ -644,25 +651,22 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
} else if (t > ref_init_start + ref_init_delay) {
ref_inited = true;
- /* update baro offset */
- baro_offset -= z_est[0];
/* set position estimate to (0, 0, 0), use GPS velocity for XY */
x_est[0] = 0.0f;
x_est[1] = gps.vel_n_m_s;
y_est[0] = 0.0f;
y_est[1] = gps.vel_e_m_s;
- z_est[0] = 0.0f;
local_pos.ref_lat = lat;
local_pos.ref_lon = lon;
- local_pos.ref_alt = alt;
+ local_pos.ref_alt = alt + z_est[0];
local_pos.ref_timestamp = t;
/* initialize projection */
map_projection_init(&ref, lat, lon);
- warnx("init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
- mavlink_log_info(mavlink_fd, "[inav] init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
+ warnx("init ref: lat=%.7f, lon=%.7f, alt=%.2f", (double)lat, (double)lon, (double)alt);
+ mavlink_log_info(mavlink_fd, "[inav] init ref: %.7f, %.7f, %.2f", (double)lat, (double)lon, (double)alt);
}
}
@@ -705,8 +709,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* save rotation matrix at this moment */
memcpy(R_gps, R_buf[est_i], sizeof(R_gps));
- w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph_m);
- w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv_m);
+ w_gps_xy = min_eph_epv / fmaxf(min_eph_epv, gps.eph);
+ w_gps_z = min_eph_epv / fmaxf(min_eph_epv, gps.epv);
}
} else {
@@ -746,10 +750,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* increase EPH/EPV on each step */
if (eph < max_eph_epv) {
- eph *= 1.0 + dt;
+ eph *= 1.0f + dt;
}
if (epv < max_eph_epv) {
- epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
+ epv += 0.005f * dt; // add 1m to EPV each 200s (baro drift)
}
/* use GPS if it's valid and reference position initialized */
@@ -758,11 +762,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* use flow if it's valid and (accurate or no GPS available) */
bool use_flow = flow_valid && (flow_accurate || !use_gps_xy);
- /* try to estimate position during some time after position sources lost */
- if (use_gps_xy || use_flow) {
- xy_src_time = t;
- }
-
bool can_estimate_xy = (eph < max_eph_epv) || use_gps_xy || use_flow;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
@@ -859,7 +858,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
inertial_filter_correct(corr_baro, dt, z_est, 0, params.w_z_baro);
if (use_gps_z) {
- epv = fminf(epv, gps.epv_m);
+ epv = fminf(epv, gps.epv);
inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
}
@@ -894,7 +893,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
if (use_gps_xy) {
- eph = fminf(eph, gps.eph_m);
+ eph = fminf(eph, gps.eph);
inertial_filter_correct(corr_gps[0][0], dt, x_est, 0, w_xy_gps_p);
inertial_filter_correct(corr_gps[1][0], dt, y_est, 0, w_xy_gps_p);
@@ -916,6 +915,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
memcpy(x_est_prev, x_est, sizeof(x_est));
memcpy(y_est_prev, y_est, sizeof(y_est));
}
+ } else {
+ /* gradually reset xy velocity estimates */
+ inertial_filter_correct(-x_est[1], dt, x_est, 1, params.w_xy_res_v);
+ inertial_filter_correct(-y_est[1], dt, y_est, 1, params.w_xy_res_v);
}
/* detect land */
@@ -931,6 +934,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
landed = false;
landed_time = 0;
}
+ /* reset xy velocity estimates when landed */
+ x_est[1] = 0.0f;
+ y_est[1] = 0.0f;
} else {
if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
@@ -955,11 +961,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float updates_dt = (t - updates_counter_start) * 0.000001f;
warnx(
"updates rate: accelerometer = %.1f/s, baro = %.1f/s, gps = %.1f/s, attitude = %.1f/s, flow = %.1f/s",
- accel_updates / updates_dt,
- baro_updates / updates_dt,
- gps_updates / updates_dt,
- attitude_updates / updates_dt,
- flow_updates / updates_dt);
+ (double)(accel_updates / updates_dt),
+ (double)(baro_updates / updates_dt),
+ (double)(gps_updates / updates_dt),
+ (double)(attitude_updates / updates_dt),
+ (double)(flow_updates / updates_dt));
updates_counter_start = t;
accel_updates = 0;
baro_updates = 0;
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index d88419c25..0581f8236 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -46,6 +46,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
+PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f);
PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f);
@@ -65,6 +66,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
+ h->w_xy_res_v = param_find("INAV_W_XY_RES_V");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
h->flow_k = param_find("INAV_FLOW_K");
@@ -87,6 +89,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
param_get(h->w_xy_flow, &(p->w_xy_flow));
+ param_get(h->w_xy_res_v, &(p->w_xy_res_v));
param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
param_get(h->flow_k, &(p->flow_k));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index df1cfaa71..423f0d879 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -47,6 +47,7 @@ struct position_estimator_inav_params {
float w_xy_gps_p;
float w_xy_gps_v;
float w_xy_flow;
+ float w_xy_res_v;
float w_gps_flow;
float w_acc_bias;
float flow_k;
@@ -66,6 +67,7 @@ struct position_estimator_inav_param_handles {
param_t w_xy_gps_p;
param_t w_xy_gps_v;
param_t w_xy_flow;
+ param_t w_xy_res_v;
param_t w_gps_flow;
param_t w_acc_bias;
param_t flow_k;
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 62e6b12cb..185cb20dd 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -47,8 +47,8 @@
#include "px4io.h"
#define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */
-#define RC_CHANNEL_HIGH_THRESH 5000
-#define RC_CHANNEL_LOW_THRESH -5000
+#define RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */
+#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */
static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len);
diff --git a/src/modules/px4iofirmware/i2c.c b/src/modules/px4iofirmware/i2c.c
index 79b6546b3..6d1d1fc2d 100644
--- a/src/modules/px4iofirmware/i2c.c
+++ b/src/modules/px4iofirmware/i2c.c
@@ -64,12 +64,15 @@
#define rCCR REG(STM32_I2C_CCR_OFFSET)
#define rTRISE REG(STM32_I2C_TRISE_OFFSET)
+void i2c_reset(void);
static int i2c_interrupt(int irq, void *context);
static void i2c_rx_setup(void);
static void i2c_tx_setup(void);
static void i2c_rx_complete(void);
static void i2c_tx_complete(void);
+#ifdef DEBUG
static void i2c_dump(void);
+#endif
static DMA_HANDLE rx_dma;
static DMA_HANDLE tx_dma;
@@ -331,6 +334,7 @@ i2c_tx_complete(void)
i2c_tx_setup();
}
+#ifdef DEBUG
static void
i2c_dump(void)
{
@@ -339,3 +343,4 @@ i2c_dump(void)
debug("CCR 0x%08x TRISE 0x%08x", rCCR, rTRISE);
debug("SR1 0x%08x SR2 0x%08x", rSR1, rSR2);
}
+#endif
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 7471faec7..d5a6b1ec4 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -312,7 +312,7 @@ struct IOPacket {
#define PKT_COUNT(_p) ((_p).count_code & PKT_COUNT_MASK)
#define PKT_CODE(_p) ((_p).count_code & PKT_CODE_MASK)
-#define PKT_SIZE(_p) ((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p)))
+#define PKT_SIZE(_p) ((size_t)((uint8_t *)&((_p).regs[PKT_COUNT(_p)]) - ((uint8_t *)&(_p))))
static const uint8_t crc8_tab[256] __attribute__((unused)) =
{
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index d4c25911e..cd134ccb4 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -37,6 +37,7 @@
*/
#include <nuttx/config.h>
+#include <nuttx/arch.h>
#include <stdio.h> // required for task_create
#include <stdbool.h>
@@ -303,14 +304,12 @@ user_start(int argc, char *argv[])
*/
if (hrt_absolute_time() - last_debug_time > (1000 * 1000)) {
- struct mallinfo minfo = mallinfo();
-
isr_debug(1, "d:%u s=0x%x a=0x%x f=0x%x m=%u",
(unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG],
(unsigned)r_status_flags,
(unsigned)r_setup_arming,
(unsigned)r_setup_features,
- (unsigned)minfo.mxordblk);
+ (unsigned)mallinfo().mxordblk);
last_debug_time = hrt_absolute_time();
}
}
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index ca175bfbc..b00a96717 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -219,8 +219,8 @@ extern bool dsm_input(uint16_t *values, uint16_t *num_values);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
-extern bool sbus1_output(uint16_t *values, uint16_t num_values);
-extern bool sbus2_output(uint16_t *values, uint16_t num_values);
+extern void sbus1_output(uint16_t *values, uint16_t num_values);
+extern void sbus2_output(uint16_t *values, uint16_t num_values);
/** global debug level for isr_debug() */
extern volatile uint8_t debug_level;
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index db1836f4a..b37259997 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -119,7 +119,6 @@ uint16_t r_page_raw_rc_input[] =
[PX4IO_P_RAW_RC_DATA] = 0,
[PX4IO_P_RAW_FRAME_COUNT] = 0,
[PX4IO_P_RAW_LOST_FRAME_COUNT] = 0,
- [PX4IO_P_RAW_RC_DATA] = 0,
[PX4IO_P_RAW_RC_BASE ... (PX4IO_P_RAW_RC_BASE + PX4IO_RC_INPUT_CHANNELS)] = 0
};
@@ -670,7 +669,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] == UINT8_MAX) {
disabled = true;
- } else if ((int)(conf[PX4IO_P_RC_CONFIG_ASSIGNMENT]) < 0 || conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
+ } else if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) {
count++;
}
@@ -712,7 +711,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
{
#define SELECT_PAGE(_page_name) \
do { \
- *values = &_page_name[0]; \
+ *values = (uint16_t *)&_page_name[0]; \
*num_values = sizeof(_page_name) / sizeof(_page_name[0]); \
} while(0)
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 0e7dc621c..0f0414148 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -116,16 +116,18 @@ sbus_init(const char *device)
return sbus_fd;
}
-bool
+void
sbus1_output(uint16_t *values, uint16_t num_values)
{
- write(sbus_fd, 'A', 1);
+ char a = 'A';
+ write(sbus_fd, &a, 1);
}
-bool
+void
sbus2_output(uint16_t *values, uint16_t num_values)
{
- write(sbus_fd, 'B', 1);
+ char b = 'B';
+ write(sbus_fd, &b, 1);
}
bool
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 577cadfbb..0d36fa2c6 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -74,6 +74,7 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <uORB/topics/satellite_info.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/optical_flow.h>
@@ -84,8 +85,10 @@
#include <uORB/topics/esc_status.h>
#include <uORB/topics/telemetry_status.h>
#include <uORB/topics/estimator_status.h>
+#include <uORB/topics/tecs_status.h>
#include <uORB/topics/system_power.h>
#include <uORB/topics/servorail_status.h>
+#include <uORB/topics/wind_estimate.h>
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
@@ -139,6 +142,8 @@ PARAM_DEFINE_INT32(SDLOG_EXT, -1);
fds[fdsc_count].events = POLLIN; \
fdsc_count++;
+#define MIN(X,Y) ((X) < (Y) ? (X) : (Y))
+
static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
@@ -939,8 +944,11 @@ int sdlog2_thread_main(int argc, char *argv[])
struct telemetry_status_s telemetry;
struct range_finder_report range_finder;
struct estimator_status_report estimator_status;
+ struct tecs_status_s tecs_status;
struct system_power_s system_power;
struct servorail_status_s servorail_status;
+ struct satellite_info_s sat_info;
+ struct wind_estimate_s wind_estimate;
} buf;
memset(&buf, 0, sizeof(buf));
@@ -971,14 +979,17 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GVSP_s log_GVSP;
struct log_BATT_s log_BATT;
struct log_DIST_s log_DIST;
- struct log_TELE_s log_TELE;
- struct log_ESTM_s log_ESTM;
+ struct log_TEL_s log_TEL;
+ struct log_EST0_s log_EST0;
+ struct log_EST1_s log_EST1;
struct log_PWR_s log_PWR;
struct log_VICN_s log_VICN;
struct log_GS0A_s log_GS0A;
struct log_GS0B_s log_GS0B;
struct log_GS1A_s log_GS1A;
struct log_GS1B_s log_GS1B;
+ struct log_TECS_s log_TECS;
+ struct log_WIND_s log_WIND;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -1000,6 +1011,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int global_pos_sub;
int triplet_sub;
int gps_pos_sub;
+ int sat_info_sub;
int vicon_pos_sub;
int flow_sub;
int rc_sub;
@@ -1007,16 +1019,19 @@ int sdlog2_thread_main(int argc, char *argv[])
int esc_sub;
int global_vel_sp_sub;
int battery_sub;
- int telemetry_sub;
+ int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
int range_finder_sub;
int estimator_status_sub;
+ int tecs_status_sub;
int system_power_sub;
int servorail_status_sub;
+ int wind_sub;
} subs;
subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
subs.status_sub = orb_subscribe(ORB_ID(vehicle_status));
subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+ subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
@@ -1034,11 +1049,17 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.esc_sub = orb_subscribe(ORB_ID(esc_status));
subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
- subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ }
subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status));
+ subs.tecs_status_sub = orb_subscribe(ORB_ID(tecs_status));
subs.system_power_sub = orb_subscribe(ORB_ID(system_power));
subs.servorail_status_sub = orb_subscribe(ORB_ID(servorail_status));
+ subs.wind_sub = orb_subscribe(ORB_ID(wind_estimate));
+ /* we need to rate-limit wind, as we do not need the full update rate */
+ orb_set_interval(subs.wind_sub, 90);
thread_running = true;
@@ -1053,11 +1074,14 @@ int sdlog2_thread_main(int argc, char *argv[])
hrt_abstime barometer_timestamp = 0;
hrt_abstime differential_pressure_timestamp = 0;
+ /* initialize calculated mean SNR */
+ float snr_mean = 0.0f;
+
/* enable logging on start if needed */
if (log_on_start) {
/* check GPS topic to get GPS time */
if (log_name_timestamp) {
- if (copy_if_updated(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos)) {
+ if (!orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos)) {
gps_time = buf_gps_pos.time_gps_usec;
}
}
@@ -1105,7 +1129,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.msg_type = LOG_STAT_MSG;
log_msg.body.log_STAT.main_state = (uint8_t) buf_status.main_state;
log_msg.body.log_STAT.arming_state = (uint8_t) buf_status.arming_state;
- log_msg.body.log_STAT.failsafe_state = (uint8_t) buf_status.failsafe_state;
+ log_msg.body.log_STAT.failsafe_state = (uint8_t) buf_status.failsafe;
log_msg.body.log_STAT.battery_remaining = buf_status.battery_remaining;
log_msg.body.log_STAT.battery_warning = (uint8_t) buf_status.battery_warning;
log_msg.body.log_STAT.landed = (uint8_t) buf_status.condition_landed;
@@ -1115,19 +1139,11 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GPS POSITION - UNIT #1 --- */
if (gps_pos_updated) {
- float snr_mean = 0.0f;
-
- for (unsigned i = 0; i < buf_gps_pos.satellites_visible; i++) {
- snr_mean += buf_gps_pos.satellite_snr[i];
- }
-
- snr_mean /= buf_gps_pos.satellites_visible;
-
log_msg.msg_type = LOG_GPS_MSG;
log_msg.body.log_GPS.gps_time = buf_gps_pos.time_gps_usec;
log_msg.body.log_GPS.fix_type = buf_gps_pos.fix_type;
- log_msg.body.log_GPS.eph = buf_gps_pos.eph_m;
- log_msg.body.log_GPS.epv = buf_gps_pos.epv_m;
+ log_msg.body.log_GPS.eph = buf_gps_pos.eph;
+ log_msg.body.log_GPS.epv = buf_gps_pos.epv;
log_msg.body.log_GPS.lat = buf_gps_pos.lat;
log_msg.body.log_GPS.lon = buf_gps_pos.lon;
log_msg.body.log_GPS.alt = buf_gps_pos.alt * 0.001f;
@@ -1135,44 +1151,55 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPS.vel_e = buf_gps_pos.vel_e_m_s;
log_msg.body.log_GPS.vel_d = buf_gps_pos.vel_d_m_s;
log_msg.body.log_GPS.cog = buf_gps_pos.cog_rad;
- log_msg.body.log_GPS.sats = buf_gps_pos.satellites_visible;
+ log_msg.body.log_GPS.sats = buf_gps_pos.satellites_used;
log_msg.body.log_GPS.snr_mean = snr_mean;
log_msg.body.log_GPS.noise_per_ms = buf_gps_pos.noise_per_ms;
log_msg.body.log_GPS.jamming_indicator = buf_gps_pos.jamming_indicator;
LOGBUFFER_WRITE_AND_COUNT(GPS);
+ }
+
+ /* --- SATELLITE INFO - UNIT #1 --- */
+ if (_extended_logging) {
+
+ if (copy_if_updated(ORB_ID(satellite_info), subs.sat_info_sub, &buf.sat_info)) {
- if (_extended_logging) {
/* log the SNR of each satellite for a detailed view of signal quality */
- unsigned gps_msg_max_snr = sizeof(buf_gps_pos.satellite_snr) / sizeof(buf_gps_pos.satellite_snr[0]);
+ unsigned sat_info_count = MIN(buf.sat_info.count, sizeof(buf.sat_info.snr) / sizeof(buf.sat_info.snr[0]));
unsigned log_max_snr = sizeof(log_msg.body.log_GS0A.satellite_snr) / sizeof(log_msg.body.log_GS0A.satellite_snr[0]);
log_msg.msg_type = LOG_GS0A_MSG;
memset(&log_msg.body.log_GS0A, 0, sizeof(log_msg.body.log_GS0A));
- /* fill set A */
- for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+ snr_mean = 0.0f;
+
+ /* fill set A and calculate mean SNR */
+ for (unsigned i = 0; i < sat_info_count; i++) {
+
+ snr_mean += buf.sat_info.snr[i];
- int satindex = buf_gps_pos.satellite_prn[i] - 1;
+ int satindex = buf.sat_info.svid[i] - 1;
/* handles index exceeding and wraps to to arithmetic errors */
if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
/* map satellites by their ID so that logs from two receivers can be compared */
- log_msg.body.log_GS0A.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ log_msg.body.log_GS0A.satellite_snr[satindex] = buf.sat_info.snr[i];
}
}
LOGBUFFER_WRITE_AND_COUNT(GS0A);
+ snr_mean /= sat_info_count;
log_msg.msg_type = LOG_GS0B_MSG;
memset(&log_msg.body.log_GS0B, 0, sizeof(log_msg.body.log_GS0B));
+
/* fill set B */
- for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+ for (unsigned i = 0; i < sat_info_count; i++) {
/* get second bank of satellites, thus deduct bank size from index */
- int satindex = buf_gps_pos.satellite_prn[i] - 1 - log_max_snr;
+ int satindex = buf.sat_info.svid[i] - 1 - log_max_snr;
/* handles index exceeding and wraps to to arithmetic errors */
if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
/* map satellites by their ID so that logs from two receivers can be compared */
- log_msg.body.log_GS0B.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ log_msg.body.log_GS0B.satellite_snr[satindex] = buf.sat_info.snr[i];
}
}
LOGBUFFER_WRITE_AND_COUNT(GS0B);
@@ -1340,7 +1367,7 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GLOBAL POSITION SETPOINT --- */
if (copy_if_updated(ORB_ID(position_setpoint_triplet), subs.triplet_sub, &buf.triplet)) {
log_msg.msg_type = LOG_GPSP_MSG;
- log_msg.body.log_GPSP.nav_state = buf.triplet.nav_state;
+ log_msg.body.log_GPSP.nav_state = 0; /* TODO: Fix this */
log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d);
log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d);
log_msg.body.log_GPSP.alt = buf.triplet.current.alt;
@@ -1381,8 +1408,8 @@ int sdlog2_thread_main(int argc, char *argv[])
if (copy_if_updated(ORB_ID(rc_channels), subs.rc_sub, &buf.rc)) {
log_msg.msg_type = LOG_RC_MSG;
/* Copy only the first 8 channels of 14 */
- memcpy(log_msg.body.log_RC.channel, buf.rc.chan, sizeof(log_msg.body.log_RC.channel));
- log_msg.body.log_RC.channel_count = buf.rc.chan_count;
+ memcpy(log_msg.body.log_RC.channel, buf.rc.channels, sizeof(log_msg.body.log_RC.channel));
+ log_msg.body.log_RC.channel_count = buf.rc.channel_count;
log_msg.body.log_RC.signal_lost = buf.rc.signal_lost;
LOGBUFFER_WRITE_AND_COUNT(RC);
}
@@ -1454,16 +1481,19 @@ int sdlog2_thread_main(int argc, char *argv[])
}
/* --- TELEMETRY --- */
- if (copy_if_updated(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry)) {
- log_msg.msg_type = LOG_TELE_MSG;
- log_msg.body.log_TELE.rssi = buf.telemetry.rssi;
- log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi;
- log_msg.body.log_TELE.noise = buf.telemetry.noise;
- log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise;
- log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors;
- log_msg.body.log_TELE.fixed = buf.telemetry.fixed;
- log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf;
- LOGBUFFER_WRITE_AND_COUNT(TELE);
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ if (copy_if_updated(telemetry_status_orb_id[i], subs.telemetry_subs[i], &buf.telemetry)) {
+ log_msg.msg_type = LOG_TEL0_MSG + i;
+ log_msg.body.log_TEL.rssi = buf.telemetry.rssi;
+ log_msg.body.log_TEL.remote_rssi = buf.telemetry.remote_rssi;
+ log_msg.body.log_TEL.noise = buf.telemetry.noise;
+ log_msg.body.log_TEL.remote_noise = buf.telemetry.remote_noise;
+ log_msg.body.log_TEL.rxerrors = buf.telemetry.rxerrors;
+ log_msg.body.log_TEL.fixed = buf.telemetry.fixed;
+ log_msg.body.log_TEL.txbuf = buf.telemetry.txbuf;
+ log_msg.body.log_TEL.heartbeat_time = buf.telemetry.heartbeat_time;
+ LOGBUFFER_WRITE_AND_COUNT(TEL);
+ }
}
/* --- BOTTOM DISTANCE --- */
@@ -1477,15 +1507,52 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- ESTIMATOR STATUS --- */
if (copy_if_updated(ORB_ID(estimator_status), subs.estimator_status_sub, &buf.estimator_status)) {
- log_msg.msg_type = LOG_ESTM_MSG;
- unsigned maxcopy = (sizeof(buf.estimator_status.states) < sizeof(log_msg.body.log_ESTM.s)) ? sizeof(buf.estimator_status.states) : sizeof(log_msg.body.log_ESTM.s);
- memset(&(log_msg.body.log_ESTM.s), 0, sizeof(log_msg.body.log_ESTM.s));
- memcpy(&(log_msg.body.log_ESTM.s), buf.estimator_status.states, maxcopy);
- log_msg.body.log_ESTM.n_states = buf.estimator_status.n_states;
- log_msg.body.log_ESTM.states_nan = buf.estimator_status.states_nan;
- log_msg.body.log_ESTM.covariance_nan = buf.estimator_status.covariance_nan;
- log_msg.body.log_ESTM.kalman_gain_nan = buf.estimator_status.kalman_gain_nan;
- LOGBUFFER_WRITE_AND_COUNT(ESTM);
+ log_msg.msg_type = LOG_EST0_MSG;
+ unsigned maxcopy0 = (sizeof(buf.estimator_status.states) < sizeof(log_msg.body.log_EST0.s)) ? sizeof(buf.estimator_status.states) : sizeof(log_msg.body.log_EST0.s);
+ memset(&(log_msg.body.log_EST0.s), 0, sizeof(log_msg.body.log_EST0.s));
+ memcpy(&(log_msg.body.log_EST0.s), buf.estimator_status.states, maxcopy0);
+ log_msg.body.log_EST0.n_states = buf.estimator_status.n_states;
+ log_msg.body.log_EST0.nan_flags = buf.estimator_status.nan_flags;
+ log_msg.body.log_EST0.health_flags = buf.estimator_status.health_flags;
+ log_msg.body.log_EST0.timeout_flags = buf.estimator_status.timeout_flags;
+ LOGBUFFER_WRITE_AND_COUNT(EST0);
+
+ log_msg.msg_type = LOG_EST1_MSG;
+ unsigned maxcopy1 = ((sizeof(buf.estimator_status.states) - maxcopy0) < sizeof(log_msg.body.log_EST1.s)) ? (sizeof(buf.estimator_status.states) - maxcopy0) : sizeof(log_msg.body.log_EST1.s);
+ memset(&(log_msg.body.log_EST1.s), 0, sizeof(log_msg.body.log_EST1.s));
+ memcpy(&(log_msg.body.log_EST1.s), buf.estimator_status.states + maxcopy0, maxcopy1);
+ LOGBUFFER_WRITE_AND_COUNT(EST1);
+ }
+
+ /* --- TECS STATUS --- */
+ if (copy_if_updated(ORB_ID(tecs_status), subs.tecs_status_sub, &buf.tecs_status)) {
+ log_msg.msg_type = LOG_TECS_MSG;
+ log_msg.body.log_TECS.altitudeSp = buf.tecs_status.altitudeSp;
+ log_msg.body.log_TECS.altitude = buf.tecs_status.altitude;
+ log_msg.body.log_TECS.flightPathAngleSp = buf.tecs_status.flightPathAngleSp;
+ log_msg.body.log_TECS.flightPathAngle = buf.tecs_status.flightPathAngle;
+ log_msg.body.log_TECS.flightPathAngleFiltered = buf.tecs_status.flightPathAngleFiltered;
+ log_msg.body.log_TECS.airspeedSp = buf.tecs_status.airspeedSp;
+ log_msg.body.log_TECS.airspeed = buf.tecs_status.airspeed;
+ log_msg.body.log_TECS.airspeedFiltered = buf.tecs_status.airspeedFiltered;
+ log_msg.body.log_TECS.airspeedDerivativeSp = buf.tecs_status.airspeedDerivativeSp;
+ log_msg.body.log_TECS.airspeedDerivative = buf.tecs_status.airspeedDerivative;
+ log_msg.body.log_TECS.totalEnergyRateSp = buf.tecs_status.totalEnergyRateSp;
+ log_msg.body.log_TECS.totalEnergyRate = buf.tecs_status.totalEnergyRate;
+ log_msg.body.log_TECS.energyDistributionRateSp = buf.tecs_status.energyDistributionRateSp;
+ log_msg.body.log_TECS.energyDistributionRate = buf.tecs_status.energyDistributionRate;
+ log_msg.body.log_TECS.mode = (uint8_t)buf.tecs_status.mode;
+ LOGBUFFER_WRITE_AND_COUNT(TECS);
+ }
+
+ /* --- WIND ESTIMATE --- */
+ if (copy_if_updated(ORB_ID(wind_estimate), subs.wind_sub, &buf.wind_estimate)) {
+ log_msg.msg_type = LOG_WIND_MSG;
+ log_msg.body.log_WIND.x = buf.wind_estimate.windspeed_north;
+ log_msg.body.log_WIND.y = buf.wind_estimate.windspeed_east;
+ log_msg.body.log_WIND.cov_x = buf.wind_estimate.covariance_north;
+ log_msg.body.log_WIND.cov_y = buf.wind_estimate.covariance_east;
+ LOGBUFFER_WRITE_AND_COUNT(WIND);
}
/* signal the other thread new data, but not yet unlock */
diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h
index dc5e6c8bd..aff0e3f48 100644
--- a/src/modules/sdlog2/sdlog2_format.h
+++ b/src/modules/sdlog2/sdlog2_format.h
@@ -91,6 +91,14 @@ struct log_format_s {
.labels = _labels \
}
+#define LOG_FORMAT_S(_name, _struct_name, _format, _labels) { \
+ .type = LOG_##_name##_MSG, \
+ .length = sizeof(struct log_##_struct_name##_s) + LOG_PACKET_HEADER_LEN, \
+ .name = #_name, \
+ .format = _format, \
+ .labels = _labels \
+ }
+
#define LOG_FORMAT_MSG 0x80
#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s)
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index f4d88f079..87f7f718f 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -276,27 +276,8 @@ struct log_DIST_s {
uint8_t flags;
};
-/* --- TELE - TELEMETRY STATUS --- */
-#define LOG_TELE_MSG 22
-struct log_TELE_s {
- uint8_t rssi;
- uint8_t remote_rssi;
- uint8_t noise;
- uint8_t remote_noise;
- uint16_t rxerrors;
- uint16_t fixed;
- uint8_t txbuf;
-};
-
-/* --- ESTM - ESTIMATOR STATUS --- */
-#define LOG_ESTM_MSG 23
-struct log_ESTM_s {
- float s[10];
- uint8_t n_states;
- uint8_t states_nan;
- uint8_t covariance_nan;
- uint8_t kalman_gain_nan;
-};
+// ID 22 available
+// ID 23 available
/* --- PWR - ONBOARD POWER SYSTEM --- */
#define LOG_PWR_MSG 24
@@ -346,6 +327,70 @@ struct log_GS1B_s {
uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
};
+/* --- TECS - TECS STATUS --- */
+#define LOG_TECS_MSG 30
+struct log_TECS_s {
+ float altitudeSp;
+ float altitude;
+ float flightPathAngleSp;
+ float flightPathAngle;
+ float flightPathAngleFiltered;
+ float airspeedSp;
+ float airspeed;
+ float airspeedFiltered;
+ float airspeedDerivativeSp;
+ float airspeedDerivative;
+
+ float totalEnergyRateSp;
+ float totalEnergyRate;
+ float energyDistributionRateSp;
+ float energyDistributionRate;
+
+ uint8_t mode;
+};
+
+/* --- WIND - WIND ESTIMATE --- */
+#define LOG_WIND_MSG 31
+struct log_WIND_s {
+ float x;
+ float y;
+ float cov_x;
+ float cov_y;
+};
+
+/* --- EST0 - ESTIMATOR STATUS --- */
+#define LOG_EST0_MSG 32
+struct log_EST0_s {
+ float s[12];
+ uint8_t n_states;
+ uint8_t nan_flags;
+ uint8_t health_flags;
+ uint8_t timeout_flags;
+};
+
+/* --- EST1 - ESTIMATOR STATUS --- */
+#define LOG_EST1_MSG 33
+struct log_EST1_s {
+ float s[16];
+};
+
+/* --- TEL0..3 - TELEMETRY STATUS --- */
+#define LOG_TEL0_MSG 34
+#define LOG_TEL1_MSG 35
+#define LOG_TEL2_MSG 36
+#define LOG_TEL3_MSG 37
+struct log_TEL_s {
+ uint8_t rssi;
+ uint8_t remote_rssi;
+ uint8_t noise;
+ uint8_t remote_noise;
+ uint16_t rxerrors;
+ uint16_t fixed;
+ uint8_t txbuf;
+ uint64_t heartbeat_time;
+};
+
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -393,14 +438,20 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
- LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"),
- LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,nStat,statNaN,covNaN,kGainNaN"),
+ LOG_FORMAT_S(TEL0, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL1, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL2, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL3, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT(EST0, "ffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,nStat,fNaN,fHealth,fTOut"),
+ LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
LOG_FORMAT(GS0A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(TECS, "ffffffffffffffB", "AltSP,Alt,FSP,F,FF,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"),
+ LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 999cf8bb3..38b190761 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -194,16 +194,25 @@ PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f);
/**
* Differential pressure sensor offset
*
+ * The offset (zero-reading) in Pascal
+ *
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f);
/**
- * Differential pressure sensor analog enabled
+ * Differential pressure sensor analog scaling
+ *
+ * Pick the appropriate scaling from the datasheet.
+ * this number defines the (linear) conversion from voltage
+ * to Pascal (pa). For the MPXV7002DP this is 1000.
+ *
+ * NOTE: If the sensor always registers zero, try switching
+ * the static and dynamic tubes.
*
* @group Sensor Calibration
*/
-PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
+PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0);
/**
@@ -243,6 +252,36 @@ PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0);
PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0);
/**
+ * Board rotation Y (Pitch) offset
+ *
+ * This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user
+ * to fine tune the board offset in the event of misalignment.
+ *
+ * @group Sensor Calibration
+ */
+ PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f);
+
+/**
+ * Board rotation X (Roll) offset
+ *
+ * This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user
+ * to fine tune the board offset in the event of misalignment.
+ *
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_FLOAT(SENS_BOARD_X_OFF, 0.0f);
+
+/**
+ * Board rotation Z (YAW) offset
+ *
+ * This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user
+ * to fine tune the board offset in the event of misalignment.
+ *
+ * @group Sensor Calibration
+ */
+PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f);
+
+/**
* External magnetometer rotation
*
* This parameter defines the rotation of the external magnetometer relative
@@ -635,6 +674,15 @@ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
/**
+ * Offboard switch channel mapping.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+
+/**
* Flaps channel mapping.
*
* @min 0
@@ -781,3 +829,20 @@ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
*
*/
PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
+
+
+/**
+ * Threshold for selecting offboard mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_OFFB_TH, 0.5f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 0ae93d7f0..388cd2dcc 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -133,7 +133,7 @@
#endif
#define BATT_V_LOWPASS 0.001f
-#define BATT_V_IGNORE_THRESHOLD 3.5f
+#define BATT_V_IGNORE_THRESHOLD 4.8f
/**
* HACK - true temperature is much less than indicated temperature in baro,
@@ -229,7 +229,7 @@ private:
math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
-
+
uint64_t _battery_discharged; /**< battery discharged current in mA*ms */
hrt_abstime _battery_current_timestamp; /**< timestamp of last battery current reading */
@@ -248,10 +248,12 @@ private:
float accel_offset[3];
float accel_scale[3];
float diff_pres_offset_pa;
- float diff_pres_analog_enabled;
+ float diff_pres_analog_scale;
int board_rotation;
int external_mag_rotation;
+
+ float board_offset[3];
int rc_map_roll;
int rc_map_pitch;
@@ -264,6 +266,7 @@ private:
int rc_map_posctl_sw;
int rc_map_loiter_sw;
int rc_map_acro_sw;
+ int rc_map_offboard_sw;
int rc_map_flaps;
@@ -280,12 +283,14 @@ private:
float rc_return_th;
float rc_loiter_th;
float rc_acro_th;
+ float rc_offboard_th;
bool rc_assist_inv;
bool rc_auto_inv;
bool rc_posctl_inv;
bool rc_return_inv;
bool rc_loiter_inv;
bool rc_acro_inv;
+ bool rc_offboard_inv;
float battery_voltage_scaling;
float battery_current_scaling;
@@ -306,7 +311,7 @@ private:
param_t mag_offset[3];
param_t mag_scale[3];
param_t diff_pres_offset_pa;
- param_t diff_pres_analog_enabled;
+ param_t diff_pres_analog_scale;
param_t rc_map_roll;
param_t rc_map_pitch;
@@ -319,6 +324,7 @@ private:
param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
param_t rc_map_acro_sw;
+ param_t rc_map_offboard_sw;
param_t rc_map_flaps;
@@ -335,12 +341,15 @@ private:
param_t rc_return_th;
param_t rc_loiter_th;
param_t rc_acro_th;
+ param_t rc_offboard_th;
param_t battery_voltage_scaling;
param_t battery_current_scaling;
param_t board_rotation;
param_t external_mag_rotation;
+
+ param_t board_offset[3];
} _parameter_handles; /**< handles for interesting parameters */
@@ -492,6 +501,7 @@ Sensors::Sensors() :
_battery_current_timestamp(0)
{
memset(&_rc, 0, sizeof(_rc));
+ memset(&_diff_pres, 0, sizeof(_diff_pres));
/* basic r/c parameters */
for (unsigned i = 0; i < _rc_max_chan_count; i++) {
@@ -536,6 +546,7 @@ Sensors::Sensors() :
_parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
_parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
+ _parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -551,6 +562,7 @@ Sensors::Sensors() :
_parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
_parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
_parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
+ _parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
@@ -579,7 +591,7 @@ Sensors::Sensors() :
/* Differential pressure offset */
_parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF");
- _parameter_handles.diff_pres_analog_enabled = param_find("SENS_DPRES_ANA");
+ _parameter_handles.diff_pres_analog_scale = param_find("SENS_DPRES_ANSC");
_parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING");
_parameter_handles.battery_current_scaling = param_find("BAT_C_SCALING");
@@ -587,6 +599,11 @@ Sensors::Sensors() :
/* rotations */
_parameter_handles.board_rotation = param_find("SENS_BOARD_ROT");
_parameter_handles.external_mag_rotation = param_find("SENS_EXT_MAG_ROT");
+
+ /* rotation offsets */
+ _parameter_handles.board_offset[0] = param_find("SENS_BOARD_X_OFF");
+ _parameter_handles.board_offset[1] = param_find("SENS_BOARD_Y_OFF");
+ _parameter_handles.board_offset[2] = param_find("SENS_BOARD_Z_OFF");
/* fetch initial parameter values */
parameters_update();
@@ -640,7 +657,7 @@ Sensors::parameters_update()
if (!isfinite(tmpScaleFactor) ||
(tmpRevFactor < 0.000001f) ||
(tmpRevFactor > 0.2f)) {
- warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, tmpScaleFactor, (int)(_parameters.rev[i]));
+ warnx("RC chan %u not sane, scaling: %8.6f, rev: %d", i, (double)tmpScaleFactor, (int)(_parameters.rev[i]));
/* scaling factors do not make sense, lock them down */
_parameters.scaling_factor[i] = 0.0f;
rc_valid = false;
@@ -698,6 +715,10 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
+ if (param_get(_parameter_handles.rc_map_offboard_sw, &(_parameters.rc_map_offboard_sw)) != OK) {
+ warnx("%s", paramerr);
+ }
+
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx("%s", paramerr);
}
@@ -726,6 +747,9 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_acro_th, &(_parameters.rc_acro_th));
_parameters.rc_acro_inv = (_parameters.rc_acro_th < 0);
_parameters.rc_acro_th = fabs(_parameters.rc_acro_th);
+ param_get(_parameter_handles.rc_offboard_th, &(_parameters.rc_offboard_th));
+ _parameters.rc_offboard_inv = (_parameters.rc_offboard_th < 0);
+ _parameters.rc_offboard_th = fabs(_parameters.rc_offboard_th);
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -738,6 +762,7 @@ Sensors::parameters_update()
_rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
_rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;
+ _rc.function[OFFBOARD] = _parameters.rc_map_offboard_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
@@ -774,7 +799,7 @@ Sensors::parameters_update()
/* Airspeed offset */
param_get(_parameter_handles.diff_pres_offset_pa, &(_parameters.diff_pres_offset_pa));
- param_get(_parameter_handles.diff_pres_analog_enabled, &(_parameters.diff_pres_analog_enabled));
+ param_get(_parameter_handles.diff_pres_analog_scale, &(_parameters.diff_pres_analog_scale));
/* scaling of ADC ticks to battery voltage */
if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) {
@@ -791,6 +816,18 @@ Sensors::parameters_update()
get_rot_matrix((enum Rotation)_parameters.board_rotation, &_board_rotation);
get_rot_matrix((enum Rotation)_parameters.external_mag_rotation, &_external_mag_rotation);
+
+ param_get(_parameter_handles.board_offset[0], &(_parameters.board_offset[0]));
+ param_get(_parameter_handles.board_offset[1], &(_parameters.board_offset[1]));
+ param_get(_parameter_handles.board_offset[2], &(_parameters.board_offset[2]));
+
+ /** fine tune board offset on parameter update **/
+ math::Matrix<3, 3> board_rotation_offset;
+ board_rotation_offset.from_euler( M_DEG_TO_RAD_F * _parameters.board_offset[0],
+ M_DEG_TO_RAD_F * _parameters.board_offset[1],
+ M_DEG_TO_RAD_F * _parameters.board_offset[2]);
+
+ _board_rotation = _board_rotation * board_rotation_offset;
return OK;
}
@@ -1202,9 +1239,9 @@ Sensors::parameter_update_poll(bool forced)
}
#if 0
- printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.chan[0].scaling_factor * 10000), (int)(_rc.chan[0].mid), (int)_rc.function[0]);
- printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.chan[1].scaling_factor * 10000), (int)(_rc.chan[1].mid), (int)_rc.function[1]);
- printf("MAN: %d %d\n", (int)(_rc.chan[0].scaled * 100), (int)(_rc.chan[1].scaled * 100));
+ printf("CH0: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[0], (int)_parameters.min[0], (int)(_rc.channels[0].scaling_factor * 10000), (int)(_rc.channels[0].mid), (int)_rc.function[0]);
+ printf("CH1: RAW MAX: %d MIN %d S: %d MID: %d FUNC: %d\n", (int)_parameters.max[1], (int)_parameters.min[1], (int)(_rc.channels[1].scaling_factor * 10000), (int)(_rc.channels[1].mid), (int)_rc.function[1]);
+ printf("MAN: %d %d\n", (int)(_rc.channels[0] * 100), (int)(_rc.channels[1] * 100));
fflush(stdout);
usleep(5000);
#endif
@@ -1287,22 +1324,23 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
/* calculate airspeed, raw is the difference from */
- float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor)
+ float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; // V_ref/4096 * (voltage divider factor)
/**
* The voltage divider pulls the signal down, only act on
* a valid voltage from a connected sensor. Also assume a non-
* zero offset from the sensor if its connected.
*/
- if (voltage > 0.4f && _parameters.diff_pres_analog_enabled) {
+ if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0.0f)) {
- float diff_pres_pa = voltage * 1000.0f - _parameters.diff_pres_offset_pa; //for MPXV7002DP sensor
+ float diff_pres_pa_raw = voltage * _parameters.diff_pres_analog_scale - _parameters.diff_pres_offset_pa;
+ float diff_pres_pa = (diff_pres_pa_raw > 0.0f) ? diff_pres_pa_raw : 0.0f;
_diff_pres.timestamp = t;
_diff_pres.differential_pressure_pa = diff_pres_pa;
- _diff_pres.differential_pressure_filtered_pa = diff_pres_pa;
+ _diff_pres.differential_pressure_raw_pa = diff_pres_pa_raw;
+ _diff_pres.differential_pressure_filtered_pa = (_diff_pres.differential_pressure_filtered_pa * 0.9f) + (diff_pres_pa * 0.1f);
_diff_pres.temperature = -1000.0f;
- _diff_pres.voltage = voltage;
/* announce the airspeed if needed, just publish else */
if (_diff_pres_pub > 0) {
@@ -1334,7 +1372,7 @@ float
Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max_value)
{
if (_rc.function[func] >= 0) {
- float value = _rc.chan[_rc.function[func]].scaled;
+ float value = _rc.channels[_rc.function[func]];
if (value < min_value) {
return min_value;
@@ -1355,7 +1393,7 @@ switch_pos_t
Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv)
{
if (_rc.function[func] >= 0) {
- float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+ float value = 0.5f * _rc.channels[_rc.function[func]] + 0.5f;
if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
@@ -1376,7 +1414,7 @@ switch_pos_t
Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
{
if (_rc.function[func] >= 0) {
- float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+ float value = 0.5f * _rc.channels[_rc.function[func]] + 0.5f;
if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
@@ -1468,25 +1506,25 @@ Sensors::rc_poll()
* DO NOT REMOVE OR ALTER STEP 1!
*/
if (rc_input.values[i] > (_parameters.trim[i] + _parameters.dz[i])) {
- _rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]);
+ _rc.channels[i] = (rc_input.values[i] - _parameters.trim[i] - _parameters.dz[i]) / (float)(_parameters.max[i] - _parameters.trim[i] - _parameters.dz[i]);
} else if (rc_input.values[i] < (_parameters.trim[i] - _parameters.dz[i])) {
- _rc.chan[i].scaled = (rc_input.values[i] - _parameters.trim[i] + _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]);
+ _rc.channels[i] = (rc_input.values[i] - _parameters.trim[i] + _parameters.dz[i]) / (float)(_parameters.trim[i] - _parameters.min[i] - _parameters.dz[i]);
} else {
/* in the configured dead zone, output zero */
- _rc.chan[i].scaled = 0.0f;
+ _rc.channels[i] = 0.0f;
}
- _rc.chan[i].scaled *= _parameters.rev[i];
+ _rc.channels[i] *= _parameters.rev[i];
/* handle any parameter-induced blowups */
- if (!isfinite(_rc.chan[i].scaled)) {
- _rc.chan[i].scaled = 0.0f;
+ if (!isfinite(_rc.channels[i])) {
+ _rc.channels[i] = 0.0f;
}
}
- _rc.chan_count = rc_input.channel_count;
+ _rc.channel_count = rc_input.channel_count;
_rc.rssi = rc_input.rssi;
_rc.signal_lost = signal_lost;
_rc.timestamp = rc_input.timestamp_last_signal;
@@ -1524,6 +1562,7 @@ Sensors::rc_poll()
manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
manual.acro_switch = get_rc_sw2pos_position(ACRO, _parameters.rc_acro_th, _parameters.rc_acro_inv);
+ manual.offboard_switch = get_rc_sw2pos_position(OFFBOARD, _parameters.rc_offboard_th, _parameters.rc_offboard_inv);
/* publish manual_control_setpoint topic */
if (_manual_control_pub > 0) {
diff --git a/src/modules/systemlib/board_serial.c b/src/modules/systemlib/board_serial.c
index ad8c2bf83..182fd15c6 100644
--- a/src/modules/systemlib/board_serial.c
+++ b/src/modules/systemlib/board_serial.c
@@ -44,11 +44,11 @@
#include "board_config.h"
#include "board_serial.h"
-int get_board_serial(char *serialid)
+int get_board_serial(uint8_t *serialid)
{
- const volatile unsigned *udid_ptr = (const unsigned *)UDID_START;
+ const volatile uint32_t *udid_ptr = (const uint32_t *)UDID_START;
union udid id;
- val_read((unsigned *)&id, udid_ptr, sizeof(id));
+ val_read((uint32_t *)&id, udid_ptr, sizeof(id));
/* Copy the serial from the chips non-write memory and swap endianess */
@@ -57,4 +57,4 @@ int get_board_serial(char *serialid)
serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8];
return 0;
-} \ No newline at end of file
+}
diff --git a/src/modules/systemlib/board_serial.h b/src/modules/systemlib/board_serial.h
index b14bb4376..873d9657b 100644
--- a/src/modules/systemlib/board_serial.h
+++ b/src/modules/systemlib/board_serial.h
@@ -44,6 +44,6 @@
__BEGIN_DECLS
-__EXPORT int get_board_serial(char *serialid);
+__EXPORT int get_board_serial(uint8_t *serialid);
__END_DECLS
diff --git a/src/modules/systemlib/circuit_breaker.c b/src/modules/systemlib/circuit_breaker.c
new file mode 100644
index 000000000..8f697749e
--- /dev/null
+++ b/src/modules/systemlib/circuit_breaker.c
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 circuit_breaker.c
+ *
+ * Circuit breaker parameters.
+ * Analog to real aviation circuit breakers these parameters
+ * allow to disable subsystems. They are not supported as standard
+ * operation procedure and are only provided for development purposes.
+ * To ensure they are not activated accidentally, the associated
+ * parameter needs to set to the key (magic).
+ */
+
+#include <systemlib/param/param.h>
+#include <systemlib/circuit_breaker.h>
+
+/**
+ * Circuit breaker for power supply check
+ *
+ * Setting this parameter to 894281 will disable the power valid
+ * checks in the commander.
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 894281
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_SUPPLY_CHK, 0);
+
+/**
+ * Circuit breaker for rate controller output
+ *
+ * Setting this parameter to 140253 will disable the rate
+ * controller uORB publication.
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 140253
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_RATE_CTRL, 0);
+
+/**
+ * Circuit breaker for IO safety
+ *
+ * Setting this parameter to 894281 will disable IO safety.
+ * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ *
+ * @min 0
+ * @max 22027
+ * @group Circuit Breaker
+ */
+PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0);
+
+bool circuit_breaker_enabled(const char* breaker, int32_t magic)
+{
+ int32_t val;
+ (void)param_get(param_find(breaker), &val);
+
+ return (val == magic);
+}
+
diff --git a/src/modules/systemlib/circuit_breaker.h b/src/modules/systemlib/circuit_breaker.h
new file mode 100644
index 000000000..1175dbce8
--- /dev/null
+++ b/src/modules/systemlib/circuit_breaker.h
@@ -0,0 +1,64 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 circuit_breaker.h
+ *
+ * Circuit breaker functionality.
+ */
+
+#ifndef CIRCUIT_BREAKER_H_
+#define CIRCUIT_BREAKER_H_
+
+/* SAFETY WARNING -- SAFETY WARNING -- SAFETY WARNING
+ *
+ * OBEY THE DOCUMENTATION FOR ALL CIRCUIT BREAKERS HERE,
+ * ENSURE TO READ CAREFULLY ALL SAFETY WARNINGS.
+ * http://pixhawk.org/dev/circuit_breakers
+ *
+ * CIRCUIT BREAKERS ARE NOT PART OF THE STANDARD OPERATION PROCEDURE
+ * AND MAY DISABLE CHECKS THAT ARE VITAL FOR SAFE FLIGHT.
+ */
+#define CBRK_SUPPLY_CHK_KEY 894281
+#define CBRK_RATE_CTRL_KEY 140253
+#define CBRK_IO_SAFETY_KEY 22027
+
+#include <stdbool.h>
+
+__BEGIN_DECLS
+
+__EXPORT bool circuit_breaker_enabled(const char* breaker, int32_t magic);
+
+__END_DECLS
+
+#endif /* CIRCUIT_BREAKER_H_ */
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index ccc516f39..7aa2f3a5f 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -67,7 +67,7 @@ __EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pT
__EXPORT struct system_load_s system_load;
-extern FAR struct _TCB *sched_gettcb(pid_t pid);
+extern FAR struct tcb_s *sched_gettcb(pid_t pid);
void cpuload_initialize_once()
{
diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c
index 6c0e876d1..998b5ac7d 100644
--- a/src/modules/systemlib/err.c
+++ b/src/modules/systemlib/err.c
@@ -86,7 +86,7 @@ warnerr_core(int errcode, const char *fmt, va_list args)
fprintf(stderr, "\n");
#elif CONFIG_ARCH_LOWPUTC
lowsyslog("%s: ", getprogname());
- lowvyslog(fmt, args);
+ lowvsyslog(fmt, args);
/* convenience as many parts of NuttX use negative errno */
if (errcode < 0)
diff --git a/src/modules/systemlib/hx_stream.c b/src/modules/systemlib/hx_stream.c
index 8e9c2bfcf..52ae77de5 100644
--- a/src/modules/systemlib/hx_stream.c
+++ b/src/modules/systemlib/hx_stream.c
@@ -63,7 +63,7 @@ struct hx_stream {
/* TX state */
int fd;
bool tx_error;
- uint8_t *tx_buf;
+ const uint8_t *tx_buf;
unsigned tx_resid;
uint32_t tx_crc;
enum {
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index 092c0e2b0..4b22a46d0 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -208,7 +208,6 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
char geomname[8];
int s[4];
int used;
- const char *end = buf + buflen;
/* enforce that the mixer ends with space or a new line */
for (int i = buflen - 1; i >= 0; i--) {
@@ -302,7 +301,6 @@ MultirotorMixer::mix(float *outputs, unsigned space)
//lowsyslog("thrust: %d, get_control3: %d\n", (int)(thrust), (int)(get_control(0, 3)));
float min_out = 0.0f;
float max_out = 0.0f;
- float scale_yaw = 1.0f;
/* perform initial mix pass yielding unbounded outputs, ignore yaw */
for (unsigned i = 0; i < _rotor_count; i++) {
@@ -327,7 +325,7 @@ MultirotorMixer::mix(float *outputs, unsigned space)
}
/* scale down roll/pitch controls if some outputs are negative, don't add yaw, keep total thrust */
- if (min_out < 0.0) {
+ if (min_out < 0.0f) {
float scale_in = thrust / (thrust - min_out);
/* mix again with adjusted controls */
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 3953b757d..147903aa0 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -1,6 +1,6 @@
############################################################################
#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# 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
@@ -52,5 +52,6 @@ SRCS = err.c \
rc_check.c \
otp.c \
board_serial.c \
- pwm_limit/pwm_limit.c
+ pwm_limit/pwm_limit.c \
+ circuit_breaker.c
diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c
index 695574fdc..0548a9f7d 100644
--- a/src/modules/systemlib/otp.c
+++ b/src/modules/systemlib/otp.c
@@ -133,7 +133,7 @@ int lock_otp(void)
// COMPLETE, BUSY, or other flash error?
-int F_GetStatus(void)
+static int F_GetStatus(void)
{
int fs = F_COMPLETE;
diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h
index f10e129d8..273b064f0 100644
--- a/src/modules/systemlib/otp.h
+++ b/src/modules/systemlib/otp.h
@@ -125,7 +125,7 @@ struct otp_lock {
#pragma pack(push, 1)
union udid {
uint32_t serial[3];
- char data[12];
+ uint8_t data[12];
};
#pragma pack(pop)
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index 7a499ca72..e44e6cdb0 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -96,8 +96,6 @@ ORB_DEFINE(parameter_update, struct parameter_update_s);
/** parameter update topic handle */
static orb_advert_t param_topic = -1;
-static sem_t param_sem = { .semcount = 1 };
-
/** lock the parameter store */
static void
param_lock(void)
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index 22182e39e..d6d8284d2 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -301,7 +301,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus\n",
handle->name,
pce->event_count,
pce->time_total,
@@ -314,7 +314,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle)
case PC_INTERVAL: {
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
- dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus\n",
handle->name,
pci->event_count,
(pci->time_last - pci->time_first) / pci->event_count,
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index 6835ee4a2..668d9dfdf 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -75,7 +75,7 @@ __EXPORT extern void perf_free(perf_counter_t handle);
/**
* Count a performance event.
*
- * This call only affects counters that take single events; PC_COUNT etc.
+ * This call only affects counters that take single events; PC_COUNT, PC_INTERVAL etc.
*
* @param handle The handle returned from perf_alloc.
*/
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
index ea5ba9e52..c733a53d7 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.c
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -97,7 +97,6 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
}
unsigned progress;
- uint16_t temp_pwm;
/* then set effective_pwm based on state */
switch (limit->state) {
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
index c0c1a5cb4..b35b333af 100644
--- a/src/modules/systemlib/rc_check.c
+++ b/src/modules/systemlib/rc_check.c
@@ -42,6 +42,7 @@
#include <stdio.h>
#include <fcntl.h>
+#include <systemlib/err.h>
#include <systemlib/rc_check.h>
#include <systemlib/param/param.h>
#include <mavlink/mavlink_log.h>
@@ -98,32 +99,32 @@ int rc_calibration_check(int mavlink_fd) {
/* assert min..center..max ordering */
if (param_min < 500) {
count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MIN < 500", i+1);
+ mavlink_log_critical(mavlink_fd, "#audio ERR: RC_%d_MIN < 500", i+1);
/* give system time to flush error message in case there are more */
usleep(100000);
}
if (param_max > 2500) {
count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_MAX > 2500", i+1);
+ mavlink_log_critical(mavlink_fd, "#audio ERR: RC_%d_MAX > 2500", i+1);
/* give system time to flush error message in case there are more */
usleep(100000);
}
if (param_trim < param_min) {
count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM < MIN (%d/%d)", i+1, (int)param_trim, (int)param_min);
+ mavlink_log_critical(mavlink_fd, "#audio ERR: RC_%d_TRIM < MIN (%d/%d)", i+1, (int)param_trim, (int)param_min);
/* give system time to flush error message in case there are more */
usleep(100000);
}
if (param_trim > param_max) {
count++;
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_TRIM > MAX (%d/%d)", i+1, (int)param_trim, (int)param_max);
+ mavlink_log_critical(mavlink_fd, "#audio ERR: RC_%d_TRIM > MAX (%d/%d)", i+1, (int)param_trim, (int)param_max);
/* give system time to flush error message in case there are more */
usleep(100000);
}
/* assert deadzone is sane */
if (param_dz > 500) {
- mavlink_log_critical(mavlink_fd, "ERR: RC_%d_DZ > 500", i+1);
+ mavlink_log_critical(mavlink_fd, "#audio ERR: RC_%d_DZ > 500", i+1);
/* give system time to flush error message in case there are more */
usleep(100000);
count++;
@@ -139,7 +140,7 @@ int rc_calibration_check(int mavlink_fd) {
/* sanity checks pass, enable channel */
if (count) {
- mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ mavlink_log_critical(mavlink_fd, "#audio ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
warnx("ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
usleep(100000);
}
diff --git a/src/modules/systemlib/state_table.h b/src/modules/systemlib/state_table.h
index f2709d29f..e6011fdef 100644
--- a/src/modules/systemlib/state_table.h
+++ b/src/modules/systemlib/state_table.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Copyright (C) 2013-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -33,8 +33,9 @@
/**
* @file state_table.h
- *
+ *
* Finite-State-Machine helper class for state table
+ * @author: Julian Oes <julian@oes.ch>
*/
#ifndef __SYSTEMLIB_STATE_TABLE_H
@@ -48,22 +49,28 @@ public:
Action action;
unsigned nextState;
};
-
+
StateTable(Tran const *table, unsigned nStates, unsigned nSignals)
: myTable(table), myNsignals(nSignals), myNstates(nStates) {}
-
+
#define NO_ACTION &StateTable::doNothing
- #define ACTION(_target) static_cast<StateTable::Action>(_target)
+ #define ACTION(_target) StateTable::Action(_target)
virtual ~StateTable() {}
-
+
void dispatch(unsigned const sig) {
- register Tran const *t = myTable + myState*myNsignals + sig;
- (this->*(t->action))();
+ /* get transition using state table */
+ Tran const *t = myTable + myState*myNsignals + sig;
+ /* accept new state */
myState = t->nextState;
+
+ /* */
+ (this->*(t->action))();
+ }
+ void doNothing() {
+ return;
}
- void doNothing() {}
protected:
unsigned myState;
private:
@@ -72,4 +79,4 @@ private:
unsigned myNstates;
};
-#endif \ No newline at end of file
+#endif
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 57a751e1c..90d8dd77c 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -54,6 +54,9 @@
#include "systemlib.h"
+// Didn't seem right to include up_internal.h, so direct extern instead.
+extern void up_systemreset(void) noreturn_function;
+
void
systemreset(bool to_bootloader)
{
@@ -64,6 +67,9 @@ systemreset(bool to_bootloader)
*(uint32_t *)0x40002850 = 0xb007b007;
}
up_systemreset();
+
+ /* lock up here */
+ while(true);
}
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index 5a5981617..cd0b30dd6 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -47,6 +47,7 @@
#include "topics/vehicle_rates_setpoint.h"
#include "topics/actuator_outputs.h"
#include "topics/encoders.h"
+#include "topics/tecs_status.h"
namespace uORB {
@@ -76,5 +77,6 @@ template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
template class __EXPORT Publication<actuator_outputs_s>;
template class __EXPORT Publication<encoders_s>;
+template class __EXPORT Publication<tecs_status_s>;
}
diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp
index c1d1a938f..44b6debc7 100644
--- a/src/modules/uORB/Subscription.cpp
+++ b/src/modules/uORB/Subscription.cpp
@@ -40,6 +40,7 @@
#include "topics/parameter_update.h"
#include "topics/actuator_controls.h"
#include "topics/vehicle_gps_position.h"
+#include "topics/satellite_info.h"
#include "topics/sensor_combined.h"
#include "topics/vehicle_attitude.h"
#include "topics/vehicle_global_position.h"
@@ -88,6 +89,7 @@ T Subscription<T>::getData() {
template class __EXPORT Subscription<parameter_update_s>;
template class __EXPORT Subscription<actuator_controls_s>;
template class __EXPORT Subscription<vehicle_gps_position_s>;
+template class __EXPORT Subscription<satellite_info_s>;
template class __EXPORT Subscription<sensor_combined_s>;
template class __EXPORT Subscription<vehicle_attitude_s>;
template class __EXPORT Subscription<vehicle_global_position_s>;
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 8340ca28a..679d6ea4f 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -79,6 +79,9 @@ ORB_DEFINE(sensor_combined, struct sensor_combined_s);
#include "topics/vehicle_gps_position.h"
ORB_DEFINE(vehicle_gps_position, struct vehicle_gps_position_s);
+#include "topics/satellite_info.h"
+ORB_DEFINE(satellite_info, struct satellite_info_s);
+
#include "topics/home_position.h"
ORB_DEFINE(home_position, struct home_position_s);
@@ -187,7 +190,10 @@ ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
#include "topics/telemetry_status.h"
-ORB_DEFINE(telemetry_status, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_0, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_1, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_2, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_3, struct telemetry_status_s);
#include "topics/debug_key_value.h"
ORB_DEFINE(debug_key_value, struct debug_key_value_s);
@@ -203,3 +209,12 @@ ORB_DEFINE(encoders, struct encoders_s);
#include "topics/estimator_status.h"
ORB_DEFINE(estimator_status, struct estimator_status_report);
+
+#include "topics/vehicle_force_setpoint.h"
+ORB_DEFINE(vehicle_force_setpoint, struct vehicle_force_setpoint_s);
+
+#include "topics/tecs_status.h"
+ORB_DEFINE(tecs_status, struct tecs_status_s);
+
+#include "topics/wind_estimate.h"
+ORB_DEFINE(wind_estimate, struct wind_estimate_s);
diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h
index 01e14cda9..cd48d3cb2 100644
--- a/src/modules/uORB/topics/differential_pressure.h
+++ b/src/modules/uORB/topics/differential_pressure.h
@@ -58,7 +58,6 @@ struct differential_pressure_s {
float differential_pressure_raw_pa; /**< Raw differential pressure reading (may be negative) */
float differential_pressure_filtered_pa; /**< Low pass filtered differential pressure reading */
float max_differential_pressure_pa; /**< Maximum differential pressure reading */
- float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */
float temperature; /**< Temperature provided by sensor, -1000.0f if unknown */
};
diff --git a/src/modules/uORB/topics/estimator_status.h b/src/modules/uORB/topics/estimator_status.h
index 5530cdb21..7f26b505b 100644
--- a/src/modules/uORB/topics/estimator_status.h
+++ b/src/modules/uORB/topics/estimator_status.h
@@ -64,9 +64,9 @@ struct estimator_status_report {
uint64_t timestamp; /**< Timestamp in microseconds since boot */
float states[32]; /**< Internal filter states */
float n_states; /**< Number of states effectively used */
- bool states_nan; /**< If set to true, one of the states is NaN */
- bool covariance_nan; /**< If set to true, the covariance matrix went NaN */
- bool kalman_gain_nan; /**< If set to true, the Kalman gain matrix went NaN */
+ uint8_t nan_flags; /**< Bitmask to indicate NaN states */
+ uint8_t health_flags; /**< Bitmask to indicate sensor health states (vel, pos, hgt) */
+ uint8_t timeout_flags; /**< Bitmask to indicate timeout flags (vel, pos, hgt) */
};
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
index 08d11abae..70071130d 100644
--- a/src/modules/uORB/topics/home_position.h
+++ b/src/modules/uORB/topics/home_position.h
@@ -59,10 +59,13 @@ struct home_position_s
{
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
- //bool altitude_is_relative; // TODO what means home relative altitude? we need clear definition of reference altitude then
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
float alt; /**< Altitude in meters */
+
+ float x; /**< X coordinate in meters */
+ float y; /**< Y coordinate in meters */
+ float z; /**< Z coordinate in meters */
};
/**
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 910b8a623..dde237adc 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -98,6 +98,7 @@ struct manual_control_setpoint_s {
switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
+ switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index ef4bc1def..e4b72f87c 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.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>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,9 @@
/**
* @file mission.h
* Definition of a mission consisting of mission items.
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_MISSION_H_
@@ -50,6 +50,7 @@
/* compatible to mavlink MAV_CMD */
enum NAV_CMD {
+ NAV_CMD_IDLE=0,
NAV_CMD_WAYPOINT=16,
NAV_CMD_LOITER_UNLIMITED=17,
NAV_CMD_LOITER_TURN_COUNT=18,
@@ -58,7 +59,8 @@ enum NAV_CMD {
NAV_CMD_LAND=21,
NAV_CMD_TAKEOFF=22,
NAV_CMD_ROI=80,
- NAV_CMD_PATHPLANNING=81
+ NAV_CMD_PATHPLANNING=81,
+ NAV_CMD_DO_JUMP=177
};
enum ORIGIN {
@@ -91,13 +93,20 @@ struct mission_item_s {
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
bool autocontinue; /**< true if next waypoint should follow after this one */
enum ORIGIN origin; /**< where the waypoint has been generated */
+ int do_jump_mission_index; /**< index where the do jump will go to */
+ unsigned do_jump_repeat_count; /**< how many times do jump needs to be done */
+ unsigned do_jump_current_count; /**< count how many times the jump has been done */
};
+/**
+ * This topic used to notify navigator about mission changes, mission itself and new mission state
+ * must be stored in dataman before publication.
+ */
struct mission_s
{
- int dataman_id; /**< default -1, there are two offboard storage places in the dataman: 0 or 1 */
- unsigned count; /**< count of the missions stored in the datamanager */
- int current_index; /**< default -1, start at the one changed latest */
+ int dataman_id; /**< default 0, there are two offboard storage places in the dataman: 0 or 1 */
+ unsigned count; /**< count of the missions stored in the dataman */
+ int current_seq; /**< default -1, start at the one changed latest */
};
/**
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index 7c3921198..beb797e62 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -53,9 +53,10 @@
struct mission_result_s
{
- bool mission_reached; /**< true if mission has been reached */
- unsigned mission_index_reached; /**< index of the mission which has been reached */
- unsigned index_current_mission; /**< index of the current mission */
+ unsigned seq_reached; /**< Sequence of the mission item which has been reached */
+ unsigned seq_current; /**< Sequence of the current mission item */
+ bool reached; /**< true if mission has been reached */
+ bool finished; /**< true if mission has been completed */
};
/**
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index 68d3e494b..d7b131e3c 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -69,7 +69,7 @@ struct offboard_control_setpoint_s {
uint64_t timestamp;
enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
- bool armed; /**< Armed flag set, yes / no */
+
float p1; /**< ailerons roll / roll rate input */
float p2; /**< elevator / pitch / pitch rate */
float p3; /**< rudder / yaw rate / yaw */
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index 34aaa30dd..673c0e491 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2013 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>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file mission_item_triplet.h
* Definition of the global WGS84 position setpoint uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#ifndef TOPIC_MISSION_ITEM_TRIPLET_H_
@@ -45,7 +46,6 @@
#include <stdint.h>
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
/**
* @addtogroup topics
@@ -54,21 +54,32 @@
enum SETPOINT_TYPE
{
- 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) */
+ SETPOINT_TYPE_POSITION = 0, /**< position setpoint */
+ SETPOINT_TYPE_VELOCITY, /**< velocity setpoint */
+ SETPOINT_TYPE_LOITER, /**< loiter setpoint */
+ SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
+ SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */
+ SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
+ SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */
};
struct position_setpoint_s
{
bool valid; /**< true if setpoint is valid */
enum SETPOINT_TYPE type; /**< setpoint type to adjust behavior of position controller */
+ float x; /**< local position setpoint in m in NED */
+ float y; /**< local position setpoint in m in NED */
+ float z; /**< local position setpoint in m in NED */
+ bool position_valid; /**< true if local position setpoint valid */
+ float vx; /**< local velocity setpoint in m in NED */
+ float vy; /**< local velocity setpoint in m in NED */
+ float vz; /**< local velocity setpoint in m in NED */
+ bool velocity_valid; /**< true if local velocity setpoint valid */
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 yawspeed; /**< yawspeed (only for multirotors, in rad/s) */
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 */
@@ -84,8 +95,6 @@ struct position_setpoint_triplet_s
struct position_setpoint_s previous;
struct position_setpoint_s current;
struct position_setpoint_s next;
-
- 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 370c54442..8978de471 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * 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
@@ -43,59 +43,43 @@
#include "../uORB.h"
/**
- * The number of RC channel inputs supported.
- * Current (Q4/2013) radios support up to 18 channels,
- * leaving at a sane value of 16.
- * This number can be greater then number of RC channels,
- * because single RC channel can be mapped to multiple
- * functions, e.g. for various mode switches.
- */
-#define RC_CHANNELS_MAPPED_MAX 16
-
-/**
* This defines the mapping of the RC functions.
* The value assigned to the specific function corresponds to the entry of
- * the channel array chan[].
+ * the channel array channels[].
*/
enum RC_CHANNELS_FUNCTION {
THROTTLE = 0,
- ROLL = 1,
- PITCH = 2,
- YAW = 3,
- MODE = 4,
- RETURN = 5,
- POSCTL = 6,
- LOITER = 7,
- OFFBOARD_MODE = 8,
- ACRO = 9,
- FLAPS = 10,
- AUX_1 = 11,
- AUX_2 = 12,
- AUX_3 = 13,
- AUX_4 = 14,
- AUX_5 = 15,
- RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
+ ROLL,
+ PITCH,
+ YAW,
+ MODE,
+ RETURN,
+ POSCTL,
+ LOITER,
+ OFFBOARD,
+ ACRO,
+ FLAPS,
+ AUX_1,
+ AUX_2,
+ AUX_3,
+ AUX_4,
+ AUX_5,
+ RC_CHANNELS_FUNCTION_MAX /**< Indicates the number of functions. There can be more functions than RC channels. */
};
/**
* @addtogroup topics
* @{
*/
-
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 */
-
- /*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 */
- bool signal_lost; /**< control signal lost, should be checked together with topic timeout */
+ uint64_t timestamp; /**< Timestamp in microseconds since boot time */
+ uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */
+ float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */
+ uint8_t channel_count; /**< Number of valid channels */
+ char function_name[RC_CHANNELS_FUNCTION_MAX][20]; /**< String array to store the names of the functions */
+ int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */
+ uint8_t rssi; /**< Receive signal strength index */
+ bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */
}; /**< radio control channels. */
/**
diff --git a/src/modules/uORB/topics/satellite_info.h b/src/modules/uORB/topics/satellite_info.h
new file mode 100644
index 000000000..37c2faa96
--- /dev/null
+++ b/src/modules/uORB/topics/satellite_info.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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>
+ *
+ * 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 satellite_info.h
+ * Definition of the GNSS satellite info uORB topic.
+ */
+
+#ifndef TOPIC_SAT_INFO_H_
+#define TOPIC_SAT_INFO_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * GNSS Satellite Info.
+ */
+
+#define SAT_INFO_MAX_SATELLITES 20
+
+struct satellite_info_s {
+ uint64_t timestamp; /**< Timestamp of satellite info */
+ uint8_t count; /**< Number of satellites in satellite info */
+ uint8_t svid[SAT_INFO_MAX_SATELLITES]; /**< Space vehicle ID [1..255], see scheme below */
+ uint8_t used[SAT_INFO_MAX_SATELLITES]; /**< 0: Satellite not used, 1: used for navigation */
+ uint8_t elevation[SAT_INFO_MAX_SATELLITES]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t azimuth[SAT_INFO_MAX_SATELLITES]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t snr[SAT_INFO_MAX_SATELLITES]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
+};
+
+/**
+ * NAV_SVINFO space vehicle ID (svid) scheme according to u-blox protocol specs
+ * u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_(UBX-13003221).pdf
+ *
+ * GPS 1-32
+ * SBAS 120-158
+ * Galileo 211-246
+ * BeiDou 159-163, 33-64
+ * QZSS 193-197
+ * GLONASS 65-96, 255
+ *
+ */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(satellite_info);
+
+#endif
diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h
new file mode 100644
index 000000000..c4d0c1874
--- /dev/null
+++ b/src/modules/uORB/topics/tecs_status.h
@@ -0,0 +1,93 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_global_position.h
+ * Definition of the global fused WGS84 position uORB topic.
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ */
+
+#ifndef TECS_STATUS_T_H_
+#define TECS_STATUS_T_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+typedef enum {
+ TECS_MODE_NORMAL,
+ TECS_MODE_UNDERSPEED,
+ TECS_MODE_TAKEOFF,
+ TECS_MODE_LAND,
+ TECS_MODE_LAND_THROTTLELIM
+} tecs_mode;
+
+ /**
+ * Internal values of the (m)TECS fixed wing speed alnd altitude control system
+ */
+struct tecs_status_s {
+ uint64_t timestamp; /**< timestamp, in microseconds since system start */
+
+ float altitudeSp;
+ float altitude;
+ float flightPathAngleSp;
+ float flightPathAngle;
+ float flightPathAngleFiltered;
+ float airspeedSp;
+ float airspeed;
+ float airspeedFiltered;
+ float airspeedDerivativeSp;
+ float airspeedDerivative;
+
+ float totalEnergyRateSp;
+ float totalEnergyRate;
+ float energyDistributionRateSp;
+ float energyDistributionRate;
+
+ tecs_mode mode;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(tecs_status);
+
+#endif
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index 76693c46e..3347724a5 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -57,6 +57,7 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
struct telemetry_status_s {
uint64_t timestamp;
+ uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
uint8_t rssi; /**< local signal strength */
uint8_t remote_rssi; /**< remote signal strength */
@@ -71,6 +72,28 @@ struct telemetry_status_s {
* @}
*/
-ORB_DECLARE(telemetry_status);
+ORB_DECLARE(telemetry_status_0);
+ORB_DECLARE(telemetry_status_1);
+ORB_DECLARE(telemetry_status_2);
+ORB_DECLARE(telemetry_status_3);
+
+#define TELEMETRY_STATUS_ORB_ID_NUM 4
+
+static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_ID_NUM] = {
+ ORB_ID(telemetry_status_0),
+ ORB_ID(telemetry_status_1),
+ ORB_ID(telemetry_status_2),
+ ORB_ID(telemetry_status_3),
+};
+
+// This is a hack to quiet an unused-variable warning for when telemetry_status.h is
+// included but telemetry_status_orb_id is not referenced. The inline works if you
+// choose to use it, but you can continue to just directly index into the array as well.
+// If you don't use the inline this ends up being a no-op with no additional code emitted.
+extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index);
+extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index)
+{
+ return telemetry_status_orb_id[index];
+}
#endif /* TOPIC_TELEMETRY_STATUS_H */
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
index d526a8ff2..8446e9c6e 100644
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -72,6 +72,8 @@ struct vehicle_attitude_setpoint_s {
float thrust; /**< Thrust in Newton the power system should generate */
bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */
+ bool pitch_reset_integral; /**< Reset pitch integral part (navigation logic change) */
+ bool yaw_reset_integral; /**< Reset yaw integral part (navigation logic change) */
};
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index ea554006f..49e2ba4b5 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -74,6 +74,7 @@ struct vehicle_control_mode_s {
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
bool flag_control_auto_enabled; /**< true if onboard autopilot should act */
+ bool flag_control_offboard_enabled; /**< true if offboard control should be used */
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
diff --git a/src/modules/uORB/topics/vehicle_force_setpoint.h b/src/modules/uORB/topics/vehicle_force_setpoint.h
new file mode 100644
index 000000000..e3a7360b2
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_force_setpoint.h
@@ -0,0 +1,65 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_force_setpoint.h
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ * Definition of force (NED) setpoint uORB topic. Typically this can be used
+ * by a position control app together with an attitude control app.
+ */
+
+#ifndef TOPIC_VEHICLE_FORCE_SETPOINT_H_
+#define TOPIC_VEHICLE_FORCE_SETPOINT_H_
+
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct vehicle_force_setpoint_s {
+ float x; /**< in N NED */
+ float y; /**< in N NED */
+ float z; /**< in N NED */
+ float yaw; /**< right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) */
+}; /**< Desired force in NED frame */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_force_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index 4897ca737..e32529cb4 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -36,7 +36,7 @@
* Definition of the global fused WGS84 position uORB topic.
*
* @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
+ * @author Julian Oes <julian@oes.ch>
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
@@ -61,15 +61,14 @@
* e.g. control inputs of the vehicle in a Kalman-filter implementation.
*/
struct vehicle_global_position_s {
- uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
-
- uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ uint64_t timestamp; /**< Time of this estimate, in microseconds since system start */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
double lat; /**< Latitude in degrees */
double lon; /**< Longitude in degrees */
float alt; /**< Altitude AMSL in meters */
- float vel_n; /**< Ground north velocity, m/s */
- float vel_e; /**< Ground east velocity, m/s */
- float vel_d; /**< Ground downside velocity, m/s */
+ float vel_n; /**< Ground north velocity, m/s */
+ float vel_e; /**< Ground east velocity, m/s */
+ float vel_d; /**< Ground downside velocity, m/s */
float yaw; /**< Yaw in radians -PI..+PI. */
float eph;
float epv;
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 5924a324d..80d65cd69 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -61,12 +61,11 @@ struct vehicle_gps_position_s {
uint64_t timestamp_variance;
float s_variance_m_s; /**< speed accuracy estimate m/s */
- float p_variance_m; /**< position accuracy estimate m */
float c_variance_rad; /**< course accuracy estimate rad */
uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
- float eph_m; /**< GPS HDOP horizontal dilution of position in m */
- float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ float eph; /**< GPS HDOP horizontal dilution of position in m */
+ float epv; /**< GPS VDOP horizontal dilution of position in m */
unsigned noise_per_ms; /**< */
unsigned jamming_indicator; /**< */
@@ -82,14 +81,7 @@ struct vehicle_gps_position_s {
uint64_t timestamp_time; /**< Timestamp for time information */
uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
- uint64_t timestamp_satellites; /**< Timestamp for sattelite information */
- uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */
- uint8_t satellite_prn[20]; /**< Global satellite ID */
- uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
- uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
- uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
- uint8_t satellite_snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
- bool satellite_info_available; /**< 0 for no info, 1 for info available */
+ uint8_t satellites_used; /**< Number of satellites used */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index ea20a317a..b46c00b75 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.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
@@ -45,6 +41,11 @@
* All apps should write to subsystem_info:
*
* (any app) --> subsystem_info (published) --> (commander app state machine) --> vehicle_status --> (mavlink app)
+ *
+ * @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 <julian@oes.ch>
*/
#ifndef VEHICLE_STATUS_H_
@@ -54,19 +55,22 @@
#include <stdbool.h>
#include "../uORB.h"
-#include <navigator/navigator_state.h>
-
/**
* @addtogroup topics @{
*/
-/* main state machine */
+/**
+ * Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
+ */
typedef enum {
MAIN_STATE_MANUAL = 0,
MAIN_STATE_ALTCTL,
MAIN_STATE_POSCTL,
- MAIN_STATE_AUTO,
+ MAIN_STATE_AUTO_MISSION,
+ MAIN_STATE_AUTO_LOITER,
+ MAIN_STATE_AUTO_RTL,
MAIN_STATE_ACRO,
+ MAIN_STATE_OFFBOARD,
MAIN_STATE_MAX
} main_state_t;
@@ -80,7 +84,7 @@ typedef enum {
ARMING_STATE_STANDBY_ERROR,
ARMING_STATE_REBOOT,
ARMING_STATE_IN_AIR_RESTORE,
- ARMING_STATE_MAX
+ ARMING_STATE_MAX,
} arming_state_t;
typedef enum {
@@ -88,13 +92,24 @@ typedef enum {
HIL_STATE_ON
} hil_state_t;
+/**
+ * Navigation state, i.e. "what should vehicle do".
+ */
typedef enum {
- FAILSAFE_STATE_NORMAL = 0, /**< Normal operation */
- FAILSAFE_STATE_RTL, /**< Return To Launch */
- FAILSAFE_STATE_LAND, /**< Land without position control */
- FAILSAFE_STATE_TERMINATION, /**< Disable motors and use parachute, can't be recovered */
- FAILSAFE_STATE_MAX
-} failsafe_state_t;
+ NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
+ NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
+ NAVIGATION_STATE_POSCTL, /**< Position control mode */
+ NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
+ NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
+ NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
+ NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
+ NAVIGATION_STATE_ACRO, /**< Acro mode */
+ NAVIGATION_STATE_LAND, /**< Land mode */
+ NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
+ NAVIGATION_STATE_TERMINATION, /**< Termination mode */
+ NAVIGATION_STATE_OFFBOARD,
+ NAVIGATION_STATE_MAX,
+} navigation_state_t;
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
@@ -154,12 +169,11 @@ struct vehicle_status_s {
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 */
- main_state_t main_state; /**< main state machine */
- unsigned int set_nav_state; /**< set navigation state machine to specified value */
- uint64_t set_nav_state_timestamp; /**< timestamp of latest change of set_nav_state */
+ main_state_t main_state; /**< main state machine */
+ navigation_state_t nav_state; /**< set navigation state machine to specified value */
arming_state_t arming_state; /**< current arming state */
- hil_state_t hil_state; /**< current hil state */
- failsafe_state_t failsafe_state; /**< current failsafe state */
+ hil_state_t hil_state; /**< current hil state */
+ bool failsafe; /**< true if system is in failsafe state */
int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
@@ -179,11 +193,15 @@ struct vehicle_status_s {
bool condition_local_altitude_valid;
bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
bool condition_landed; /**< true if vehicle is landed, always true if disarmed */
+ bool condition_power_input_valid; /**< set if input power is valid */
+ float avionics_power_rail_voltage; /**< voltage of the avionics power rail */
bool rc_signal_found_once;
bool rc_signal_lost; /**< true if RC reception lost */
bool rc_input_blocked; /**< set if RC input should be ignored */
+ bool data_link_lost; /**< datalink to GCS lost */
+
bool offboard_control_signal_found_once;
bool offboard_control_signal_lost;
bool offboard_control_signal_weak;
@@ -206,6 +224,8 @@ struct vehicle_status_s {
uint16_t errors_count2;
uint16_t errors_count3;
uint16_t errors_count4;
+
+ bool circuit_breaker_engaged_power_check;
};
/**
diff --git a/src/modules/mavlink/util.h b/src/modules/uORB/topics/wind_estimate.h
index 5ca9a085d..58333a64f 100644
--- a/src/modules/mavlink/util.h
+++ b/src/modules/uORB/topics/wind_estimate.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -32,22 +32,37 @@
****************************************************************************/
/**
- * @file util.h
- * Utility and helper functions and data.
+ * @file wind_estimate.h
+ *
+ * Wind estimate topic topic
+ *
*/
-#pragma once
+#ifndef TOPIC_WIND_ESTIMATE_H
+#define TOPIC_WIND_ESTIMATE_H
-/** MAVLink communications channel */
-extern uint8_t chan;
+#include <stdint.h>
+#include "../uORB.h"
-/** Shutdown marker */
-extern volatile bool thread_should_exit;
+/**
+ * @addtogroup topics
+ * @{
+ */
-/** Waypoint storage */
-extern mavlink_wpm_storage *wpm;
+/** Wind estimate */
+struct wind_estimate_s {
+
+ uint64_t timestamp; /**< Microseconds since system boot */
+ float windspeed_north; /**< Wind component in north / X direction */
+ float windspeed_east; /**< Wind component in east / Y direction */
+ float covariance_north; /**< Uncertainty - set to zero (no uncertainty) if not estimated */
+ float covariance_east; /**< Uncertainty - set to zero (no uncertainty) if not estimated */
+};
/**
- * Translate the custom state into standard mavlink modes and state.
+ * @}
*/
-extern void get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode);
+
+ORB_DECLARE(wind_estimate);
+
+#endif \ No newline at end of file