aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-05-29 11:26:18 +0200
committerLorenz Meier <lm@inf.ethz.ch>2014-05-29 11:26:18 +0200
commit6341737384b5bf39ee664c924ee930b875aa19ab (patch)
treed3ab6db7962a5d7f5c3eda4f5319df7060477d8d /src
parentaf1af1e22ddd4bcd55fe9eaaf98f4a640329a4c7 (diff)
parent83edab4d593b2cb92dae713d705255aeca4b3040 (diff)
downloadpx4-firmware-6341737384b5bf39ee664c924ee930b875aa19ab.tar.gz
px4-firmware-6341737384b5bf39ee664c924ee930b875aa19ab.tar.bz2
px4-firmware-6341737384b5bf39ee664c924ee930b875aa19ab.zip
Merge branch 'master' of github.com:PX4/Firmware into pca8574
Diffstat (limited to 'src')
-rw-r--r--src/drivers/ardrone_interface/ardrone_interface.c2
-rw-r--r--src/drivers/ardrone_interface/module.mk1
-rw-r--r--src/drivers/blinkm/blinkm.cpp71
-rw-r--r--src/drivers/boards/aerocore/aerocore_init.c282
-rw-r--r--src/drivers/boards/aerocore/aerocore_led.c (renamed from src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c)142
-rw-r--r--[-rwxr-xr-x]src/drivers/boards/aerocore/aerocore_pwm_servo.c (renamed from src/modules/position_estimator_mc/position_estimator_mc_params.h)106
-rw-r--r--src/drivers/boards/aerocore/aerocore_spi.c183
-rw-r--r--src/drivers/boards/aerocore/board_config.h176
-rw-r--r--src/drivers/boards/aerocore/module.mk8
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h5
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h9
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c12
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu_spi.c35
-rw-r--r--src/drivers/drv_gpio.h10
-rw-r--r--src/drivers/drv_gps.h4
-rw-r--r--src/drivers/drv_hrt.h1
-rw-r--r--src/drivers/ets_airspeed/ets_airspeed.cpp10
-rw-r--r--src/drivers/frsky_telemetry/frsky_data.c17
-rw-r--r--src/drivers/frsky_telemetry/frsky_telemetry.c2
-rw-r--r--src/drivers/frsky_telemetry/module.mk2
-rw-r--r--src/drivers/gps/gps.cpp35
-rw-r--r--src/drivers/gps/gps_helper.cpp4
-rw-r--r--src/drivers/gps/gps_helper.h8
-rw-r--r--src/drivers/gps/module.mk2
-rw-r--r--src/drivers/gps/mtk.cpp10
-rw-r--r--src/drivers/gps/ubx.cpp47
-rw-r--r--src/drivers/gps/ubx.h28
-rw-r--r--src/drivers/hil/hil.cpp2
-rw-r--r--src/drivers/hmc5883/hmc5883.cpp10
-rw-r--r--src/drivers/hott/messages.cpp32
-rw-r--r--src/drivers/l3gd20/l3gd20.cpp56
-rw-r--r--src/drivers/lsm303d/lsm303d.cpp2
-rw-r--r--src/drivers/mkblctrl/mkblctrl.cpp38
-rw-r--r--src/drivers/mpu6000/mpu6000.cpp1
-rw-r--r--src/drivers/ms5611/ms5611.cpp9
-rw-r--r--src/drivers/ms5611/ms5611_spi.cpp2
-rw-r--r--src/drivers/px4fmu/fmu.cpp340
-rw-r--r--src/drivers/px4fmu/module.mk2
-rw-r--r--src/drivers/px4io/module.mk2
-rw-r--r--src/drivers/px4io/px4io.cpp85
-rw-r--r--src/drivers/px4io/px4io_serial.cpp2
-rw-r--r--src/drivers/sf0x/sf0x.cpp7
-rw-r--r--src/drivers/stm32/adc/adc.cpp6
-rw-r--r--src/drivers/stm32/drv_hrt.c14
-rw-r--r--src/examples/fixedwing_control/module.mk2
-rw-r--r--src/examples/flow_position_control/flow_position_control_main.c613
-rw-r--r--src/examples/flow_position_control/flow_position_control_params.c124
-rw-r--r--src/examples/flow_position_control/flow_position_control_params.h100
-rw-r--r--src/examples/flow_position_control/module.mk41
-rw-r--r--src/examples/flow_position_estimator/flow_position_estimator_main.c5
-rw-r--r--src/examples/px4_daemon_app/module.mk2
-rw-r--r--src/examples/px4_daemon_app/px4_daemon_app.c2
-rw-r--r--src/examples/px4_mavlink_debug/module.mk4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp21
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp23
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h4
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp20
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h4
-rw-r--r--src/lib/geo/geo.h2
-rw-r--r--src/lib/geo/geo_mag_declination.c136
-rw-r--r--src/lib/geo/geo_mag_declination.h (renamed from src/modules/fixedwing_att_control/fixedwing_att_control_rate.h)25
-rw-r--r--src/lib/geo/module.mk3
-rw-r--r--src/lib/mathlib/CMSIS/Include/arm_math.h2
-rw-r--r--src/lib/version/version.h4
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.cpp812
-rw-r--r--src/modules/att_pos_estimator_ekf/KalmanNav.hpp194
-rw-r--r--src/modules/att_pos_estimator_ekf/kalman_main.cpp157
-rw-r--r--src/modules/att_pos_estimator_ekf/module.mk42
-rw-r--r--src/modules/att_pos_estimator_ekf/params.c49
-rwxr-xr-xsrc/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp25
-rw-r--r--src/modules/attitude_estimator_ekf/module.mk2
-rwxr-xr-xsrc/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp9
-rw-r--r--src/modules/attitude_estimator_so3/module.mk2
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp66
-rw-r--r--src/modules/commander/airspeed_calibration.cpp6
-rw-r--r--src/modules/commander/commander.cpp338
-rw-r--r--src/modules/commander/commander_helper.cpp38
-rw-r--r--src/modules/commander/commander_tests/state_machine_helper_test.cpp24
-rw-r--r--src/modules/commander/gyro_calibration.cpp18
-rw-r--r--src/modules/commander/mag_calibration.cpp47
-rw-r--r--src/modules/commander/module.mk4
-rw-r--r--src/modules/commander/px4_custom_mode.h5
-rw-r--r--src/modules/commander/rc_calibration.cpp6
-rw-r--r--src/modules/commander/state_machine_helper.cpp166
-rw-r--r--src/modules/dataman/dataman.c52
-rw-r--r--src/modules/dataman/dataman.h20
-rw-r--r--src/modules/dataman/module.mk2
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp (renamed from src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp)465
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c271
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator.cpp2609
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator.h (renamed from src/modules/fw_att_pos_estimator/estimator.h)129
-rw-r--r--src/modules/ekf_att_pos_estimator/module.mk (renamed from src/modules/fw_att_pos_estimator/module.mk)8
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.c169
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_att.h51
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_main.c367
-rw-r--r--src/modules/fixedwing_att_control/fixedwing_att_control_rate.c211
-rw-r--r--src/modules/fixedwing_att_control/module.mk42
-rw-r--r--src/modules/fixedwing_backside/fixedwing.cpp4
-rw-r--r--src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c479
-rw-r--r--src/modules/fixedwing_pos_control/module.mk40
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp88
-rw-r--r--src/modules/fw_att_pos_estimator/estimator.cpp2248
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp152
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c11
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.cpp34
-rw-r--r--src/modules/fw_pos_control_l1/landingslope.h31
-rw-r--r--src/modules/mavlink/mavlink_main.cpp42
-rw-r--r--src/modules/mavlink/mavlink_main.h5
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp53
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.cpp2
-rw-r--r--src/modules/mavlink/mavlink_orb_subscription.h2
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp20
-rw-r--r--src/modules/mavlink/mavlink_stream.cpp4
-rw-r--r--src/modules/mavlink/mavlink_stream.h6
-rw-r--r--src/modules/mavlink/module.mk2
-rw-r--r--src/modules/mc_att_control/mc_att_control_main.cpp106
-rw-r--r--src/modules/mc_att_control/mc_att_control_params.c48
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp12
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_params.c12
-rw-r--r--src/modules/navigator/geofence.cpp5
-rw-r--r--src/modules/navigator/geofence.h5
-rw-r--r--src/modules/navigator/geofence_params.c1
-rw-r--r--src/modules/navigator/mission_feasibility_checker.cpp59
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h13
-rw-r--r--src/modules/navigator/module.mk2
-rw-r--r--src/modules/navigator/navigator_main.cpp14
-rw-r--r--src/modules/navigator/navigator_mission.cpp3
-rw-r--r--src/modules/navigator/navigator_mission.h3
-rw-r--r--src/modules/navigator/navigator_params.c3
-rw-r--r--src/modules/navigator/navigator_state.h42
-rw-r--r--src/modules/position_estimator/module.mk44
-rw-r--r--src/modules/position_estimator/position_estimator_main.c423
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.c15
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.h2
-rw-r--r--src/modules/position_estimator_inav/module.mk2
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c91
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c6
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h4
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1.c58
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1.h30
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.h30
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.h30
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe1_types.h16
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2.c119
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2.h32
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.h32
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.h32
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe2_types.h16
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3.c137
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3.h33
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_data.c32
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_data.h38
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.c47
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.h33
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.h33
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/kalman_dlqe3_types.h16
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D.c136
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.c157
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_types.h16
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.c31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.h31
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/positionKalmanFilter1D_types.h16
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/randn.c524
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/randn.h33
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rtGetInf.c139
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rtGetInf.h23
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rtGetNaN.c96
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rtGetNaN.h21
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rt_nonfinite.c87
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rt_nonfinite.h53
-rwxr-xr-xsrc/modules/position_estimator_mc/codegen/rtwtypes.h159
-rwxr-xr-xsrc/modules/position_estimator_mc/kalman_dlqe1.m3
-rwxr-xr-xsrc/modules/position_estimator_mc/kalman_dlqe2.m9
-rwxr-xr-xsrc/modules/position_estimator_mc/kalman_dlqe3.m17
-rw-r--r--src/modules/position_estimator_mc/module.mk60
-rwxr-xr-xsrc/modules/position_estimator_mc/positionKalmanFilter1D.m19
-rwxr-xr-xsrc/modules/position_estimator_mc/positionKalmanFilter1D_dT.m26
-rwxr-xr-xsrc/modules/position_estimator_mc/position_estimator_mc_main.c515
-rwxr-xr-xsrc/modules/position_estimator_mc/position_estimator_mc_params.c68
-rw-r--r--src/modules/px4iofirmware/controls.c7
-rw-r--r--src/modules/px4iofirmware/mixer.cpp16
-rw-r--r--src/modules/px4iofirmware/protocol.h14
-rw-r--r--src/modules/px4iofirmware/px4io.h2
-rw-r--r--src/modules/px4iofirmware/registers.c39
-rw-r--r--src/modules/px4iofirmware/sbus.c15
-rw-r--r--src/modules/sdlog/module.mk43
-rw-r--r--src/modules/sdlog/sdlog.c840
-rw-r--r--src/modules/sdlog/sdlog_ringbuffer.c91
-rw-r--r--src/modules/sdlog/sdlog_ringbuffer.h91
-rw-r--r--src/modules/sdlog2/module.mk2
-rw-r--r--src/modules/sdlog2/sdlog2.c230
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h41
-rw-r--r--src/modules/segway/BlockSegwayController.cpp4
-rw-r--r--src/modules/sensors/module.mk2
-rw-r--r--src/modules/sensors/sensor_params.c132
-rw-r--r--src/modules/sensors/sensors.cpp264
-rw-r--r--src/modules/systemlib/mixer/mixer.h3
-rw-r--r--src/modules/systemlib/mixer/mixer_load.c1
-rw-r--r--src/modules/systemlib/mixer/mixer_multirotor.cpp112
-rwxr-xr-xsrc/modules/systemlib/mixer/multi_tables15
-rw-r--r--src/modules/systemlib/param/param.c64
-rw-r--r--src/modules/systemlib/perf_counter.c16
-rw-r--r--src/modules/systemlib/perf_counter.h14
-rw-r--r--src/modules/systemlib/pid/pid.c2
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.c14
-rw-r--r--src/modules/systemlib/rc_check.c2
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h44
-rw-r--r--src/modules/uORB/topics/rc_channels.h19
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h5
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_status.h5
-rw-r--r--src/systemcmds/config/config.c43
-rw-r--r--src/systemcmds/esc_calib/esc_calib.c2
-rw-r--r--src/systemcmds/hw_ver/hw_ver.c73
-rw-r--r--src/systemcmds/mtd/24xxxx_mtd.c36
-rw-r--r--src/systemcmds/mtd/mtd.c4
-rw-r--r--src/systemcmds/nshterm/module.mk2
-rw-r--r--src/systemcmds/param/module.mk3
-rw-r--r--src/systemcmds/param/param.c39
-rw-r--r--src/systemcmds/perf/module.mk2
-rw-r--r--src/systemcmds/perf/perf.c2
-rw-r--r--src/systemcmds/preflight_check/module.mk2
-rw-r--r--src/systemcmds/pwm/module.mk2
-rw-r--r--src/systemcmds/pwm/pwm.c106
-rw-r--r--src/systemcmds/reboot/module.mk2
-rw-r--r--src/systemcmds/tests/test_mtd.c17
-rw-r--r--src/systemcmds/tests/tests_main.c2
-rw-r--r--src/systemcmds/top/module.mk2
-rw-r--r--src/systemcmds/ver/module.mk (renamed from src/systemcmds/hw_ver/module.mk)11
-rw-r--r--src/systemcmds/ver/ver.c123
244 files changed, 7346 insertions, 12191 deletions
diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c
index b88f61ce8..e5bb772b3 100644
--- a/src/drivers/ardrone_interface/ardrone_interface.c
+++ b/src/drivers/ardrone_interface/ardrone_interface.c
@@ -119,7 +119,7 @@ int ardrone_interface_main(int argc, char *argv[])
ardrone_interface_task = task_spawn_cmd("ardrone_interface",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 15,
- 2048,
+ 1100,
ardrone_interface_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/drivers/ardrone_interface/module.mk b/src/drivers/ardrone_interface/module.mk
index 058bd1397..d8e6c76c6 100644
--- a/src/drivers/ardrone_interface/module.mk
+++ b/src/drivers/ardrone_interface/module.mk
@@ -38,3 +38,4 @@
MODULE_COMMAND = ardrone_interface
SRCS = ardrone_interface.c \
ardrone_motor_control.c
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp
index b75c2297f..5c502f682 100644
--- a/src/drivers/blinkm/blinkm.cpp
+++ b/src/drivers/blinkm/blinkm.cpp
@@ -194,6 +194,26 @@ private:
bool systemstate_run;
+ int vehicle_status_sub_fd;
+ int vehicle_control_mode_sub_fd;
+ int vehicle_gps_position_sub_fd;
+ int actuator_armed_sub_fd;
+ int safety_sub_fd;
+
+ int num_of_cells;
+ int detected_cells_runcount;
+
+ int t_led_color[8];
+ int t_led_blink;
+ int led_thread_runcount;
+ int led_interval;
+
+ bool topic_initialized;
+ bool detected_cells_blinked;
+ bool led_thread_ready;
+
+ int num_of_used_sats;
+
void setLEDColor(int ledcolor);
static void led_trampoline(void *arg);
void led();
@@ -265,7 +285,22 @@ BlinkM::BlinkM(int bus, int blinkm) :
led_color_7(LED_OFF),
led_color_8(LED_OFF),
led_blink(LED_NOBLINK),
- systemstate_run(false)
+ systemstate_run(false),
+ vehicle_status_sub_fd(-1),
+ vehicle_control_mode_sub_fd(-1),
+ vehicle_gps_position_sub_fd(-1),
+ actuator_armed_sub_fd(-1),
+ safety_sub_fd(-1),
+ num_of_cells(0),
+ detected_cells_runcount(0),
+ t_led_color({0}),
+ t_led_blink(0),
+ led_thread_runcount(0),
+ led_interval(1000),
+ topic_initialized(false),
+ detected_cells_blinked(false),
+ led_thread_ready(true),
+ num_of_used_sats(0)
{
memset(&_work, 0, sizeof(_work));
}
@@ -382,31 +417,6 @@ void
BlinkM::led()
{
- static int vehicle_status_sub_fd;
- static int vehicle_control_mode_sub_fd;
- static int vehicle_gps_position_sub_fd;
- static int actuator_armed_sub_fd;
- static int safety_sub_fd;
-
- static int num_of_cells = 0;
- static int detected_cells_runcount = 0;
-
- static int t_led_color[8] = { 0, 0, 0, 0, 0, 0, 0, 0};
- static int t_led_blink = 0;
- static int led_thread_runcount=0;
- static int led_interval = 1000;
-
- static int no_data_vehicle_status = 0;
- static int no_data_vehicle_control_mode = 0;
- static int no_data_actuator_armed = 0;
- static int no_data_vehicle_gps_position = 0;
-
- static bool topic_initialized = false;
- static bool detected_cells_blinked = false;
- static bool led_thread_ready = true;
-
- int num_of_used_sats = 0;
-
if(!topic_initialized) {
vehicle_status_sub_fd = orb_subscribe(ORB_ID(vehicle_status));
orb_set_interval(vehicle_status_sub_fd, 250);
@@ -494,6 +504,11 @@ BlinkM::led()
orb_check(vehicle_status_sub_fd, &new_data_vehicle_status);
+ int no_data_vehicle_status = 0;
+ int no_data_vehicle_control_mode = 0;
+ int no_data_actuator_armed = 0;
+ int no_data_vehicle_gps_position = 0;
+
if (new_data_vehicle_status) {
orb_copy(ORB_ID(vehicle_status), vehicle_status_sub_fd, &vehicle_status_raw);
no_data_vehicle_status = 0;
@@ -638,11 +653,11 @@ BlinkM::led()
if(new_data_vehicle_control_mode || no_data_vehicle_control_mode < 3) {
/* indicate main control state */
- if (vehicle_status_raw.main_state == MAIN_STATE_EASY)
+ if (vehicle_status_raw.main_state == MAIN_STATE_POSCTL)
led_color_4 = LED_GREEN;
else if (vehicle_status_raw.main_state == MAIN_STATE_AUTO)
led_color_4 = LED_BLUE;
- else if (vehicle_status_raw.main_state == MAIN_STATE_SEATBELT)
+ else if (vehicle_status_raw.main_state == MAIN_STATE_ALTCTL)
led_color_4 = LED_YELLOW;
else if (vehicle_status_raw.main_state == MAIN_STATE_MANUAL)
led_color_4 = LED_WHITE;
diff --git a/src/drivers/boards/aerocore/aerocore_init.c b/src/drivers/boards/aerocore/aerocore_init.c
new file mode 100644
index 000000000..4e3ba2d7e
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_init.c
@@ -0,0 +1,282 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file aerocore_init.c
+ *
+ * AeroCore-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialisation.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+#include <nuttx/gran.h>
+
+#include <stm32.h>
+#include "board_config.h"
+#include <stm32_uart.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
+
+#include <systemlib/cpuload.h>
+#include <systemlib/perf_counter.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+#if defined(CONFIG_FAT_DMAMEMORY)
+# if !defined(CONFIG_GRAN) || !defined(CONFIG_FAT_DMAMEMORY)
+# error microSD DMA support requires CONFIG_GRAN
+# endif
+
+static GRAN_HANDLE dma_allocator;
+
+/*
+ * The DMA heap size constrains the total number of things that can be
+ * ready to do DMA at a time.
+ *
+ * For example, FAT DMA depends on one sector-sized buffer per filesystem plus
+ * one sector-sized buffer per file.
+ *
+ * We use a fundamental alignment / granule size of 64B; this is sufficient
+ * to guarantee alignment for the largest STM32 DMA burst (16 beats x 32bits).
+ */
+static uint8_t g_dma_heap[8192] __attribute__((aligned(64)));
+static perf_counter_t g_dma_perf;
+
+static void
+dma_alloc_init(void)
+{
+ dma_allocator = gran_initialize(g_dma_heap,
+ sizeof(g_dma_heap),
+ 7, /* 128B granule - must be > alignment (XXX bug?) */
+ 6); /* 64B alignment */
+ if (dma_allocator == NULL) {
+ message("[boot] DMA allocator setup FAILED");
+ } else {
+ g_dma_perf = perf_alloc(PC_COUNT, "DMA allocations");
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/*
+ * DMA-aware allocator stubs for the FAT filesystem.
+ */
+
+__EXPORT void *fat_dma_alloc(size_t size);
+__EXPORT void fat_dma_free(FAR void *memory, size_t size);
+
+void *
+fat_dma_alloc(size_t size)
+{
+ perf_count(g_dma_perf);
+ return gran_alloc(dma_allocator, size);
+}
+
+void
+fat_dma_free(FAR void *memory, size_t size)
+{
+ gran_free(dma_allocator, memory, size);
+}
+
+#else
+
+# define dma_alloc_init()
+
+#endif
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+__EXPORT void
+stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi3;
+static struct spi_dev_s *spi4;
+
+#include <math.h>
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+__EXPORT int nsh_archinitialize(void)
+{
+
+ /* configure ADC pins */
+ stm32_configgpio(GPIO_ADC1_IN10); /* used by VBUS valid */
+ stm32_configgpio(GPIO_ADC1_IN11); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN12); /* J1 breakout */
+ stm32_configgpio(GPIO_ADC1_IN13); /* J1 breakout */
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* configure the DMA allocator */
+ dma_alloc_init();
+
+ /* configure CPU load estimation */
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+#endif
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+ led_off(LED_AMBER);
+
+ /* Configure Sensors on SPI bus #3 */
+ spi3 = up_spiinitialize(3);
+ if (!spi3) {
+ message("[boot] FAILED to initialize SPI port 3\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: 1MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi3, 10000000);
+ SPI_SETBITS(spi3, 8);
+ SPI_SETMODE(spi3, SPIDEV_MODE3);
+ SPI_SELECT(spi3, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_ACCEL_MAG, false);
+ SPI_SELECT(spi3, PX4_SPIDEV_BARO, false);
+ up_udelay(20);
+ message("[boot] Initialized SPI port 3 (SENSORS)\n");
+
+ /* Configure FRAM on SPI bus #4 */
+ spi4 = up_spiinitialize(4);
+ if (!spi4) {
+ message("[boot] FAILED to initialize SPI port 4\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ /* Default: ~10MHz, 8 bits, Mode 3 */
+ SPI_SETFREQUENCY(spi4, 10 * 1000 * 1000);
+ SPI_SETBITS(spi4, 8);
+ SPI_SETMODE(spi4, SPIDEV_MODE0);
+ SPI_SELECT(spi4, SPIDEV_FLASH, false);
+ message("[boot] Initialized SPI port 4 (FRAM)\n");
+
+ return OK;
+}
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c b/src/drivers/boards/aerocore/aerocore_led.c
index 6138ef39c..e40d1730c 100644
--- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_params.c
+++ b/src/drivers/boards/aerocore/aerocore_led.c
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013, 2014 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
@@ -32,86 +32,90 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_params.c
+ * @file aerocore_led.c
*
- * Parameters defined by the attitude and position estimator task
- *
- * @author Lorenz Meier <lm@inf.ethz.ch>
+ * AeroCore LED backend.
*/
#include <nuttx/config.h>
-#include <systemlib/param/param.h>
+#include <stdbool.h>
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include <arch/board/board.h>
/*
- * Estimator parameters, accessible via MAVLink
- *
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
*/
+__BEGIN_DECLS
+extern void led_init();
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
-/**
- * Velocity estimate delay
- *
- * The delay in milliseconds of the velocity estimate from GPS.
- *
- * @min 0
- * @max 1000
- * @group Position Estimator
- */
-PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230);
+__EXPORT void led_init()
+{
+ stm32_configgpio(GPIO_LED0);
+ stm32_configgpio(GPIO_LED1);
+}
-/**
- * Position estimate delay
- *
- * The delay in milliseconds of the position estimate from GPS.
- *
- * @min 0
- * @max 1000
- * @group Position Estimator
- */
-PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210);
+__EXPORT void led_on(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
-/**
- * Height estimate delay
- *
- * The delay in milliseconds of the height estimate from the barometer.
- *
- * @min 0
- * @max 1000
- * @group Position Estimator
- */
-PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350);
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
-/**
- * Mag estimate delay
- *
- * The delay in milliseconds of the magnetic field estimate from
- * the magnetometer.
- *
- * @min 0
- * @max 1000
- * @group Position Estimator
- */
-PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30);
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
-/**
- * True airspeeed estimate delay
- *
- * The delay in milliseconds of the airspeed estimate.
- *
- * @min 0
- * @max 1000
- * @group Position Estimator
- */
-PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
+__EXPORT void led_off(int led)
+{
+ switch (led) {
+ case 0:
+ stm32_gpiowrite(GPIO_LED0, false);
+ break;
-/**
- * GPS vs. barometric altitude update weight
- *
- * RE-CHECK this.
- *
- * @min 0.0
- * @max 1.0
- * @group Position Estimator
- */
-PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
+ case 1:
+ stm32_gpiowrite(GPIO_LED1, false);
+ break;
+
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
+
+__EXPORT void led_toggle(int led)
+{
+ switch (led) {
+ case 0:
+ if (stm32_gpioread(GPIO_LED0))
+ stm32_gpiowrite(GPIO_LED0, false);
+ else
+ stm32_gpiowrite(GPIO_LED0, true);
+ break;
+
+ case 1:
+ if (stm32_gpioread(GPIO_LED1))
+ stm32_gpiowrite(GPIO_LED1, false);
+ else
+ stm32_gpiowrite(GPIO_LED1, true);
+ break;
+ default:
+ warnx("LED ID not recognized\n");
+ }
+}
diff --git a/src/modules/position_estimator_mc/position_estimator_mc_params.h b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
index c4c95f7b4..251eaff7b 100755..100644
--- a/src/modules/position_estimator_mc/position_estimator_mc_params.h
+++ b/src/drivers/boards/aerocore/aerocore_pwm_servo.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Damian Aregger <daregger@student.ethz.ch>
- * Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,35 +32,86 @@
****************************************************************************/
/*
- * @file position_estimator_mc_params.h
- *
- * Parameters for Position Estimator
+ * @file aerocore_pwm_servo.c
+ *
+ * Configuration data for the stm32 pwm_servo driver.
+ *
+ * Note that these arrays must always be fully-sized.
*/
-#include <systemlib/param/param.h>
+#include <stdint.h>
-struct position_estimator_mc_params {
- float addNoise;
- float sigma;
- float R;
- int baro; /* consider barometer */
-};
+#include <stm32.h>
+#include <stm32_gpio.h>
+#include <stm32_tim.h>
-struct position_estimator_mc_param_handles {
- param_t addNoise;
- param_t sigma;
- param_t r;
- param_t baro_param_handle;
-};
+#include <drivers/stm32/drv_pwm_servo.h>
+#include <drivers/drv_pwm_output.h>
-/**
- * Initialize all parameter handles and values
- *
- */
-int parameters_init(struct position_estimator_mc_param_handles *h);
+#include "board_config.h"
-/**
- * Update all parameters
- *
- */
-int parameters_update(const struct position_estimator_mc_param_handles *h, struct position_estimator_mc_params *p);
+__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = {
+ {
+ .base = STM32_TIM1_BASE,
+ .clock_register = STM32_RCC_APB2ENR,
+ .clock_bit = RCC_APB2ENR_TIM1EN,
+ .clock_freq = STM32_APB2_TIM1_CLKIN
+ },
+ {
+ .base = STM32_TIM3_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM3EN,
+ .clock_freq = STM32_APB1_TIM3_CLKIN
+ }
+};
+
+__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
+ {
+ .gpio = GPIO_TIM1_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM1_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH1OUT,
+ .timer_index = 1,
+ .timer_channel = 1,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH2OUT,
+ .timer_index = 1,
+ .timer_channel = 2,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH3OUT,
+ .timer_index = 1,
+ .timer_channel = 3,
+ .default_value = 1500,
+ },
+ {
+ .gpio = GPIO_TIM3_CH4OUT,
+ .timer_index = 1,
+ .timer_channel = 4,
+ .default_value = 1500,
+ }
+};
diff --git a/src/drivers/boards/aerocore/aerocore_spi.c b/src/drivers/boards/aerocore/aerocore_spi.c
new file mode 100644
index 000000000..e329bd9d1
--- /dev/null
+++ b/src/drivers/boards/aerocore/aerocore_spi.c
@@ -0,0 +1,183 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file aerocore_spi.c
+ *
+ * Board-specific SPI functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include <up_arch.h>
+#include <chip.h>
+#include <stm32.h>
+#include "board_config.h"
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+__EXPORT void weak_function stm32_spiinitialize(void)
+{
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(GPIO_SPI1_NSS);
+ stm32_gpiowrite(GPIO_SPI1_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(GPIO_SPI2_NSS);
+ stm32_gpiowrite(GPIO_SPI2_NSS, 1);
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
+ stm32_configgpio(GPIO_SPI_CS_BARO);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+
+ stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
+ stm32_configgpio(GPIO_EXTI_MAG_DRDY);
+ stm32_configgpio(GPIO_EXTI_ACCEL_DRDY);
+#endif
+
+#ifdef CONFIG_STM32_SPI4
+ stm32_configgpio(GPIO_SPI4_NSS);
+ stm32_gpiowrite(GPIO_SPI4_NSS, 1);
+#endif
+}
+
+#ifdef CONFIG_STM32_SPI1
+__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI1_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there is only one device broken-out so select it */
+ stm32_gpiowrite(GPIO_SPI2_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+__EXPORT void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_ACCEL_MAG:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
+ break;
+
+ case PX4_SPIDEV_BARO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
+ break;
+
+ default:
+ break;
+ }
+}
+
+__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+
+#ifdef CONFIG_STM32_SPI4
+__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI4_NSS, !selected);
+}
+
+__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* FRAM is always present */
+ return SPI_STATUS_PRESENT;
+}
+#endif
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
new file mode 100644
index 000000000..70142a314
--- /dev/null
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -0,0 +1,176 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file board_config.h
+ *
+ * AeroCore internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+#define UDID_START 0x1FFF7A10
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+
+/* LEDs */
+#define GPIO_LED0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN9)
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN10)
+
+/* Gyro */
+#define GPIO_EXTI_GYRO_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN0)
+#define SENSOR_BOARD_ROTATION_DEFAULT 3 /* SENSOR_BOARD_ROTATION_270_DEG */
+
+/* Accel & Mag */
+#define GPIO_EXTI_MAG_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN1)
+#define GPIO_EXTI_ACCEL_DRDY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN2)
+
+/* GPS */
+#define GPIO_GPS_NRESET (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPS_TIMEPULSE (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTC|GPIO_PIN4)
+#define GPS_DEFAULT_UART_PORT "/dev/ttyS0"
+
+/* SPI3--Sensors */
+#define PX4_SPI_BUS_SENSORS 3
+#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN2)
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
+#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
+
+/* Nominal chip selects for devices on SPI bus #3 */
+#define PX4_SPIDEV_ACCEL_MAG 0
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_BARO 2
+
+/* User GPIOs broken out on J11 */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN8)
+
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN12)
+#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN13)
+#define GPIO_GPIO8_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN14)
+#define GPIO_GPIO9_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN15)
+#define GPIO_GPIO10_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_GPIO11_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN8)
+
+/* PWM
+ *
+ * Eight PWM outputs are configured.
+ *
+ * Pins:
+ *
+ * CH1 : PA8 : TIM1_CH1
+ * CH2 : PA9 : TIM1_CH2
+ * CH3 : PA10 : TIM1_CH3
+ * CH4 : PA11 : TIM1_CH4
+ * CH5 : PC6 : TIM3_CH1
+ * CH6 : PC7 : TIM3_CH2
+ * CH7 : PC8 : TIM3_CH3
+ * CH8 : PC9 : TIM3_CH4
+ */
+#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_1
+#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_1
+#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_1
+#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_1
+#define GPIO_TIM3_CH1OUT GPIO_TIM3_CH1OUT_3
+#define GPIO_TIM3_CH2OUT GPIO_TIM3_CH2OUT_3
+#define GPIO_TIM3_CH3OUT GPIO_TIM3_CH3OUT_2
+#define GPIO_TIM3_CH4OUT GPIO_TIM3_CH4OUT_2
+
+/* High-resolution timer */
+#define HRT_TIMER 8 /* use timer 8 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+
+/* Tone Alarm (no onboard speaker )*/
+#define TONE_ALARM_TIMER 2 /* timer 2 */
+#define TONE_ALARM_CHANNEL 1 /* channel 1 */
+#define GPIO_TONE_ALARM_IDLE (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF1|GPIO_SPEED_2MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/aerocore/module.mk b/src/drivers/boards/aerocore/module.mk
new file mode 100644
index 000000000..b53fe0a29
--- /dev/null
+++ b/src/drivers/boards/aerocore/module.mk
@@ -0,0 +1,8 @@
+#
+# Board-specific startup code for the AeroCore
+#
+
+SRCS = aerocore_init.c \
+ aerocore_pwm_servo.c \
+ aerocore_spi.c \
+ aerocore_led.c
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 02c26b5c0..c944007a5 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -85,6 +85,9 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+#define PX4_SPI_BUS_SENSORS 1
+#define PX4_SPI_BUS_EXT 2
+
/*
* Use these in place of the spi_dev_e enumeration to
* select a specific SPI device on SPI1
@@ -96,7 +99,7 @@ __BEGIN_DECLS
/*
* Optional devices on IO's external port
*/
-#define PX4_SPIDEV_ACCEL_MAG 2
+#define PX4_SPIDEV_ACCEL_MAG 2
/*
* I2C busses
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 7cfca7656..36eb7bec4 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -106,6 +106,11 @@ __BEGIN_DECLS
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
+#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
+
+#define PX4_SPI_BUS_SENSORS 1
+#define PX4_SPI_BUS_EXT 4
/* Use these in place of the spi_dev_e enumeration to select a specific SPI device on SPI1 */
#define PX4_SPIDEV_GYRO 1
@@ -113,6 +118,10 @@ __BEGIN_DECLS
#define PX4_SPIDEV_BARO 3
#define PX4_SPIDEV_MPU 4
+/* External bus */
+#define PX4_SPIDEV_EXT0 1
+#define PX4_SPIDEV_EXT1 2
+
/* I2C busses */
#define PX4_I2C_BUS_EXPANSION 1
#define PX4_I2C_BUS_LED 2
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
index 71414d62c..bf41bb1fe 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c
@@ -192,6 +192,7 @@ stm32_boardinitialize(void)
static struct spi_dev_s *spi1;
static struct spi_dev_s *spi2;
+static struct spi_dev_s *spi4;
static struct sdio_dev_s *sdio;
#include <math.h>
@@ -305,6 +306,17 @@ __EXPORT int nsh_archinitialize(void)
message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n");
+ spi4 = up_spiinitialize(4);
+
+ /* Default SPI4 to 1MHz and de-assert the known chip selects. */
+ SPI_SETFREQUENCY(spi4, 10000000);
+ SPI_SETBITS(spi4, 8);
+ SPI_SETMODE(spi4, SPIDEV_MODE3);
+ SPI_SELECT(spi4, PX4_SPIDEV_EXT0, false);
+ SPI_SELECT(spi4, PX4_SPIDEV_EXT1, false);
+
+ message("[boot] Initialized SPI port 4\n");
+
#ifdef CONFIG_MMCSD
/* First, get an instance of the SDIO interface */
diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
index c66c490a7..01dbd6e77 100644
--- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
+++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c
@@ -94,6 +94,13 @@ __EXPORT void weak_function stm32_spiinitialize(void)
stm32_configgpio(GPIO_SPI_CS_FRAM);
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1);
#endif
+
+#ifdef CONFIG_STM32_SPI4
+ stm32_configgpio(GPIO_SPI_CS_EXT0);
+ stm32_configgpio(GPIO_SPI_CS_EXT1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+#endif
}
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
@@ -157,3 +164,31 @@ __EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devi
return SPI_STATUS_PRESENT;
}
#endif
+
+__EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_EXT0:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1);
+ break;
+
+ case PX4_SPIDEV_EXT1:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1);
+ break;
+
+ default:
+ break;
+
+ }
+}
+
+__EXPORT uint8_t stm32_spi4status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
diff --git a/src/drivers/drv_gpio.h b/src/drivers/drv_gpio.h
index f60964c2b..5acd0d343 100644
--- a/src/drivers/drv_gpio.h
+++ b/src/drivers/drv_gpio.h
@@ -94,6 +94,14 @@
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+/*
+ * AeroCore GPIO numbers and configuration.
+ *
+ */
+# define PX4FMU_DEVICE_PATH "/dev/px4fmu"
+#endif
+
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
/* no GPIO driver on the PX4IOv1 board */
#endif
@@ -146,4 +154,4 @@
#define GPIO_SENSOR_RAIL_RESET GPIOC(13)
-#endif /* _DRV_GPIO_H */ \ No newline at end of file
+#endif /* _DRV_GPIO_H */
diff --git a/src/drivers/drv_gps.h b/src/drivers/drv_gps.h
index 06e3535b3..e14f4e00d 100644
--- a/src/drivers/drv_gps.h
+++ b/src/drivers/drv_gps.h
@@ -43,10 +43,14 @@
#include <stdint.h>
#include <sys/ioctl.h>
+#include "board_config.h"
+
#include "drv_sensor.h"
#include "drv_orb_dev.h"
+#ifndef GPS_DEFAULT_UART_PORT
#define GPS_DEFAULT_UART_PORT "/dev/ttyS3"
+#endif
#define GPS_DEVICE_PATH "/dev/gps"
diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h
index d130d68b3..8bfc90c64 100644
--- a/src/drivers/drv_hrt.h
+++ b/src/drivers/drv_hrt.h
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <stdbool.h>
+#include <inttypes.h>
#include <time.h>
#include <queue.h>
diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp
index 146a06e7c..2de7063ea 100644
--- a/src/drivers/ets_airspeed/ets_airspeed.cpp
+++ b/src/drivers/ets_airspeed/ets_airspeed.cpp
@@ -154,8 +154,9 @@ ETSAirspeed::collect()
return ret;
}
- uint16_t diff_pres_pa = val[1] << 8 | val[0];
- if (diff_pres_pa == 0) {
+ uint16_t diff_pres_pa_raw = val[1] << 8 | val[0];
+ uint16_t diff_pres_pa;
+ if (diff_pres_pa_raw == 0) {
// a zero value means the pressure sensor cannot give us a
// value. We need to return, and not report a value or the
// caller could end up using this value as part of an
@@ -165,10 +166,10 @@ ETSAirspeed::collect()
return -1;
}
- if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
+ if (diff_pres_pa_raw < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) {
diff_pres_pa = 0;
} else {
- diff_pres_pa -= _diff_pres_offset;
+ diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset;
}
// Track maximum differential pressure measured (so we can work out top speed).
@@ -183,6 +184,7 @@ ETSAirspeed::collect()
// XXX we may want to smooth out the readings to remove noise.
report.differential_pressure_filtered_pa = (float)diff_pres_pa;
+ report.differential_pressure_raw_pa = (float)diff_pres_pa_raw;
report.temperature = -1000.0f;
report.voltage = 0;
report.max_differential_pressure_pa = _max_differential_pressure_pa;
diff --git a/src/drivers/frsky_telemetry/frsky_data.c b/src/drivers/frsky_telemetry/frsky_data.c
index 57a03bc84..dd9b90fb3 100644
--- a/src/drivers/frsky_telemetry/frsky_data.c
+++ b/src/drivers/frsky_telemetry/frsky_data.c
@@ -53,6 +53,8 @@
#include <uORB/topics/vehicle_global_position.h>
#include <uORB/topics/vehicle_status.h>
+#include <drivers/drv_hrt.h>
+
/* FrSky sensor hub data IDs */
#define FRSKY_ID_GPS_ALT_BP 0x01
#define FRSKY_ID_TEMP1 0x02
@@ -192,17 +194,12 @@ void frsky_send_frame1(int uart)
}
/**
- * Formats the decimal latitude/longitude to the required degrees/minutes/seconds.
+ * Formats the decimal latitude/longitude to the required degrees/minutes.
*/
static float frsky_format_gps(float dec)
{
- float dms_deg = (int) dec;
- float dec_deg = dec - dms_deg;
- float dms_min = (int) (dec_deg * 60);
- float dec_min = (dec_deg * 60) - dms_min;
- float dms_sec = dec_min * 60;
-
- return (dms_deg * 100.0f) + dms_min + (dms_sec / 100.0f);
+ float dm_deg = (int) dec;
+ return (dm_deg * 100.0f) + (dec - dm_deg) * 60;
}
/**
@@ -230,9 +227,9 @@ void frsky_send_frame2(int uart)
struct tm *tm_gps = gmtime(&time_gps);
course = (global_pos.yaw + M_PI_F) / M_PI_F * 180.0f;
- lat = frsky_format_gps(abs(global_pos.lat));
+ lat = frsky_format_gps(fabsf(global_pos.lat));
lat_ns = (global_pos.lat < 0) ? 'S' : 'N';
- lon = frsky_format_gps(abs(global_pos.lon));
+ lon = frsky_format_gps(fabsf(global_pos.lon));
lon_ew = (global_pos.lon < 0) ? 'W' : 'E';
speed = sqrtf(global_pos.vel_n * global_pos.vel_n + global_pos.vel_e * global_pos.vel_e)
* 25.0f / 46.0f;
diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c
index 7b08ca69e..6e0839043 100644
--- a/src/drivers/frsky_telemetry/frsky_telemetry.c
+++ b/src/drivers/frsky_telemetry/frsky_telemetry.c
@@ -222,7 +222,7 @@ int frsky_telemetry_main(int argc, char *argv[])
frsky_task = task_spawn_cmd("frsky_telemetry",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 2000,
frsky_telemetry_thread_main,
(const char **)argv);
diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk
index 1632c74f7..9a49589ee 100644
--- a/src/drivers/frsky_telemetry/module.mk
+++ b/src/drivers/frsky_telemetry/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = frsky_telemetry
SRCS = frsky_data.c \
frsky_telemetry.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp
index a902bdf2f..5342ccf78 100644
--- a/src/drivers/gps/gps.cpp
+++ b/src/drivers/gps/gps.cpp
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -56,6 +56,7 @@
#include <arch/board/board.h>
#include <drivers/drv_hrt.h>
#include <drivers/device/i2c.h>
+#include <systemlib/systemlib.h>
#include <systemlib/perf_counter.h>
#include <systemlib/scheduling_priorities.h>
#include <systemlib/err.h>
@@ -63,6 +64,8 @@
#include <uORB/uORB.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <board_config.h>
+
#include "ubx.h"
#include "mtk.h"
@@ -76,12 +79,6 @@
#endif
static const int ERROR = -1;
-#ifndef CONFIG_SCHED_WORKQUEUE
-# error This requires CONFIG_SCHED_WORKQUEUE.
-#endif
-
-
-
class GPS : public device::CDev
{
public:
@@ -209,7 +206,8 @@ GPS::init()
goto out;
/* start the GPS driver worker task */
- _task = task_create("gps", SCHED_PRIORITY_SLOW_DRIVER, 2048, (main_t)&GPS::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("gps", SCHED_DEFAULT,
+ SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr);
if (_task < 0) {
warnx("task start failed: %d", errno);
@@ -276,14 +274,14 @@ GPS::task_main()
_report.timestamp_position = hrt_absolute_time();
_report.lat = (int32_t)47.378301e7f;
_report.lon = (int32_t)8.538777e7f;
- _report.alt = (int32_t)400e3f;
+ _report.alt = (int32_t)1200e3f;
_report.timestamp_variance = hrt_absolute_time();
_report.s_variance_m_s = 10.0f;
_report.p_variance_m = 10.0f;
_report.c_variance_rad = 0.1f;
_report.fix_type = 3;
- _report.eph_m = 3.0f;
- _report.epv_m = 7.0f;
+ _report.eph_m = 0.9f;
+ _report.epv_m = 1.8f;
_report.timestamp_velocity = hrt_absolute_time();
_report.vel_n_m_s = 0.0f;
_report.vel_e_m_s = 0.0f;
@@ -421,7 +419,14 @@ GPS::task_main()
void
GPS::cmd_reset()
{
- //XXX add reset?
+#ifdef GPIO_GPS_NRESET
+ warnx("Toggling GPS reset pin");
+ stm32_configgpio(GPIO_GPS_NRESET);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 0);
+ usleep(100);
+ stm32_gpiowrite(GPIO_GPS_NRESET, 1);
+ warnx("Toggled GPS reset pin");
+#endif
}
void
@@ -443,10 +448,10 @@ GPS::print_info()
warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK");
if (_report.timestamp_position != 0) {
- warnx("position lock: %dD, satellites: %d, last update: %fms ago", (int)_report.fix_type,
- _report.satellites_visible, (hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
+ warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type,
+ _report.satellites_visible, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f);
warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt);
- warnx("eph: %.2fm, epv: %.2fm", _report.eph_m, _report.epv_m);
+ warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m);
warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate());
warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate());
warnx("rate publication:\t%6.2f Hz", (double)_rate);
diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp
index 2360ff39b..3b92f1bf4 100644
--- a/src/drivers/gps/gps_helper.cpp
+++ b/src/drivers/gps/gps_helper.cpp
@@ -56,7 +56,7 @@ GPS_Helper::get_velocity_update_rate()
return _rate_vel;
}
-float
+void
GPS_Helper::reset_update_rates()
{
_rate_count_vel = 0;
@@ -64,7 +64,7 @@ GPS_Helper::reset_update_rates()
_interval_rate_start = hrt_absolute_time();
}
-float
+void
GPS_Helper::store_update_rates()
{
_rate_vel = _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f);
diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h
index cfb9e0d43..d14a95afe 100644
--- a/src/drivers/gps/gps_helper.h
+++ b/src/drivers/gps/gps_helper.h
@@ -46,13 +46,17 @@
class GPS_Helper
{
public:
+
+ GPS_Helper() {};
+ virtual ~GPS_Helper() {};
+
virtual int configure(unsigned &baud) = 0;
virtual int receive(unsigned timeout) = 0;
int set_baudrate(const int &fd, unsigned baud);
float get_position_update_rate();
float get_velocity_update_rate();
- float reset_update_rates();
- float store_update_rates();
+ void reset_update_rates();
+ void store_update_rates();
protected:
uint8_t _rate_count_lat_lon;
diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk
index 82c67d40a..eb382c4b2 100644
--- a/src/drivers/gps/module.mk
+++ b/src/drivers/gps/module.mk
@@ -41,3 +41,5 @@ SRCS = gps.cpp \
gps_helper.cpp \
mtk.cpp \
ubx.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp
index c90ecbe28..680f00d97 100644
--- a/src/drivers/gps/mtk.cpp
+++ b/src/drivers/gps/mtk.cpp
@@ -249,12 +249,18 @@ MTK::handle_message(gps_mtk_packet_t &packet)
warnx("mtk: unknown revision");
_gps_position->lat = 0;
_gps_position->lon = 0;
+
+ // Indicate this data is not usable and bail out
+ _gps_position->eph_m = 1000.0f;
+ _gps_position->epv_m = 1000.0f;
+ _gps_position->fix_type = 0;
+ return;
}
_gps_position->alt = (int32_t)(packet.msl_altitude * 10); // from cm to mm
_gps_position->fix_type = packet.fix_type;
- _gps_position->eph_m = packet.hdop; // XXX: Check this because eph_m is in m and hdop is without unit
- _gps_position->epv_m = 0.0; //unknown in mtk custom mode
+ _gps_position->eph_m = packet.hdop / 100.0f; // from cm to m
+ _gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph
_gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s
_gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad
_gps_position->satellites_visible = packet.satellites;
diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp
index 8a2afecb7..19cf5beec 100644
--- a/src/drivers/gps/ubx.cpp
+++ b/src/drivers/gps/ubx.cpp
@@ -164,7 +164,7 @@ UBX::configure(unsigned &baudrate)
send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet));
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: configuration failed: RATE");
+ warnx("CFG FAIL: RATE");
return 1;
}
@@ -185,7 +185,7 @@ UBX::configure(unsigned &baudrate)
send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet));
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: configuration failed: NAV5");
+ warnx("CFG FAIL: NAV5");
return 1;
}
@@ -194,35 +194,42 @@ UBX::configure(unsigned &baudrate)
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV POSLLH");
+ warnx("MSG CFG FAIL: NAV POSLLH");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV TIMEUTC");
+ warnx("MSG CFG FAIL: NAV TIMEUTC");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SOL");
+ warnx("MSG CFG FAIL: NAV SOL");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV VELNED");
+ warnx("MSG CFG FAIL: NAV VELNED");
return 1;
}
configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5);
if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
- warnx("ubx: msg rate configuration failed: NAV SVINFO");
+ warnx("MSG CFG FAIL: NAV SVINFO");
+ return 1;
+ }
+
+ configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1);
+
+ if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) {
+ warnx("MSG CFG FAIL: MON HW");
return 1;
}
@@ -274,7 +281,7 @@ UBX::receive(unsigned timeout)
if (ret < 0) {
/* something went wrong when polling */
- warnx("ubx: poll error");
+ warnx("poll error");
return -1;
} else if (ret == 0) {
@@ -310,7 +317,7 @@ UBX::receive(unsigned timeout)
/* abort after timeout if no useful packets received */
if (time_started + timeout * 1000 < hrt_absolute_time()) {
- warnx("ubx: timeout - no useful messages");
+ warnx("timeout - no useful messages");
return -1;
}
}
@@ -383,7 +390,7 @@ UBX::parse_char(uint8_t b)
return 1; // message received successfully
} else {
- warnx("ubx: checksum wrong");
+ warnx("checksum wrong");
decode_init();
return -1;
}
@@ -392,7 +399,7 @@ UBX::parse_char(uint8_t b)
_rx_count++;
} else {
- warnx("ubx: buffer full");
+ warnx("buffer full");
decode_init();
return -1;
}
@@ -566,6 +573,24 @@ UBX::handle_message()
break;
}
+ case UBX_CLASS_MON: {
+ switch (_message_id) {
+ case UBX_MESSAGE_MON_HW: {
+
+ struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer;
+
+ _gps_position->noise_per_ms = p->noisePerMS;
+ _gps_position->jamming_indicator = p->jamInd;
+
+ ret = 1;
+ break;
+ }
+
+ default:
+ break;
+ }
+ }
+
default:
break;
}
diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h
index 79a904f4a..5cf47b60b 100644
--- a/src/drivers/gps/ubx.h
+++ b/src/drivers/gps/ubx.h
@@ -56,6 +56,7 @@
//#define UBX_CLASS_RXM 0x02
#define UBX_CLASS_ACK 0x05
#define UBX_CLASS_CFG 0x06
+#define UBX_CLASS_MON 0x0A
/* MessageIDs (the ones that are used) */
#define UBX_MESSAGE_NAV_POSLLH 0x02
@@ -72,6 +73,8 @@
#define UBX_MESSAGE_CFG_RATE 0x08
#define UBX_MESSAGE_CFG_NAV5 0x24
+#define UBX_MESSAGE_MON_HW 0x09
+
#define UBX_CFG_PRT_LENGTH 20
#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */
#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */
@@ -210,6 +213,27 @@ typedef struct {
uint8_t ck_b;
} gps_bin_nav_velned_packet_t;
+struct gps_bin_mon_hw_packet {
+ uint32_t pinSel;
+ uint32_t pinBank;
+ uint32_t pinDir;
+ uint32_t pinVal;
+ uint16_t noisePerMS;
+ uint16_t agcCnt;
+ uint8_t aStatus;
+ uint8_t aPower;
+ uint8_t flags;
+ uint8_t __reserved1;
+ uint32_t usedMask;
+ uint8_t VP[25];
+ uint8_t jamInd;
+ uint16_t __reserved3;
+ uint32_t pinIrq;
+ uint32_t pulLH;
+ uint32_t pullL;
+};
+
+
//typedef struct {
// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */
// int16_t week; /**< Measurement GPS week number */
@@ -319,7 +343,7 @@ typedef enum {
//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t;
#pragma pack(pop)
-#define RECV_BUFFER_SIZE 500 //The NAV-SOL messages really need such a big buffer
+#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer
class UBX : public GPS_Helper
{
@@ -383,7 +407,7 @@ private:
uint8_t _message_class;
uint8_t _message_id;
unsigned _payload_size;
- uint8_t _disable_cmd_last;
+ hrt_abstime _disable_cmd_last;
};
#endif /* UBX_H_ */
diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp
index 0a047f38f..55cc077fb 100644
--- a/src/drivers/hil/hil.cpp
+++ b/src/drivers/hil/hil.cpp
@@ -122,7 +122,7 @@ private:
actuator_controls_s _controls;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp
index cdc9d3106..fddba806e 100644
--- a/src/drivers/hmc5883/hmc5883.cpp
+++ b/src/drivers/hmc5883/hmc5883.cpp
@@ -158,6 +158,7 @@ private:
int _class_instance;
orb_advert_t _mag_topic;
+ orb_advert_t _subsystem_pub;
perf_counter_t _sample_perf;
perf_counter_t _comms_errors;
@@ -324,7 +325,9 @@ HMC5883::HMC5883(int bus) :
_reports(nullptr),
_range_scale(0), /* default range scale from counts to gauss */
_range_ga(1.3f),
+ _collect_phase(false),
_mag_topic(-1),
+ _subsystem_pub(-1),
_class_instance(-1),
_sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")),
_comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")),
@@ -1137,13 +1140,12 @@ int HMC5883::check_calibration()
true,
_calibrated,
SUBSYSTEM_TYPE_MAG};
- static orb_advert_t pub = -1;
if (!(_pub_blocked)) {
- if (pub > 0) {
- orb_publish(ORB_ID(subsystem_info), pub, &info);
+ if (_subsystem_pub > 0) {
+ orb_publish(ORB_ID(subsystem_info), _subsystem_pub, &info);
} else {
- pub = orb_advertise(ORB_ID(subsystem_info), &info);
+ _subsystem_pub = orb_advertise(ORB_ID(subsystem_info), &info);
}
}
}
diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp
index 90a744015..1e779e8dc 100644
--- a/src/drivers/hott/messages.cpp
+++ b/src/drivers/hott/messages.cpp
@@ -51,6 +51,8 @@
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_gps_position.h>
+#include <drivers/drv_hrt.h>
+
/* The board is very roughly 5 deg warmer than the surrounding air */
#define BOARD_TEMP_OFFSET_DEG 5
@@ -62,7 +64,6 @@ static int _airspeed_sub = -1;
static int _esc_sub = -1;
static orb_advert_t _esc_pub;
-struct esc_status_s _esc;
static bool _home_position_set = false;
static double _home_lat = 0.0d;
@@ -82,8 +83,6 @@ init_sub_messages(void)
void
init_pub_messages(void)
{
- memset(&_esc, 0, sizeof(_esc));
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
}
void
@@ -106,23 +105,26 @@ publish_gam_message(const uint8_t *buffer)
size_t size = sizeof(msg);
memset(&msg, 0, size);
memcpy(&msg, buffer, size);
+ struct esc_status_s esc;
+ memset(&esc, 0, sizeof(esc));
+
+ // Publish it.
+ esc.timestamp = hrt_absolute_time();
+ esc.esc_count = 1;
+ esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
+
+ esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
+ esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
+ esc.esc[0].esc_temperature = msg.temperature1 - 20;
+ esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
+ esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
/* announce the esc if needed, just publish else */
if (_esc_pub > 0) {
- orb_publish(ORB_ID(esc_status), _esc_pub, &_esc);
+ orb_publish(ORB_ID(esc_status), _esc_pub, &esc);
} else {
- _esc_pub = orb_advertise(ORB_ID(esc_status), &_esc);
+ _esc_pub = orb_advertise(ORB_ID(esc_status), &esc);
}
-
- // Publish it.
- _esc.esc_count = 1;
- _esc.esc_connectiontype = ESC_CONNECTION_TYPE_PPM;
-
- _esc.esc[0].esc_vendor = ESC_VENDOR_GRAUPNER_HOTT;
- _esc.esc[0].esc_rpm = (uint16_t)((msg.rpm_H << 8) | (msg.rpm_L & 0xff)) * 10;
- _esc.esc[0].esc_temperature = msg.temperature1 - 20;
- _esc.esc[0].esc_voltage = (uint16_t)((msg.main_voltage_H << 8) | (msg.main_voltage_L & 0xff));
- _esc.esc[0].esc_current = (uint16_t)((msg.current_H << 8) | (msg.current_L & 0xff));
}
void
diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp
index 90c3db9ae..37e72388b 100644
--- a/src/drivers/l3gd20/l3gd20.cpp
+++ b/src/drivers/l3gd20/l3gd20.cpp
@@ -34,6 +34,9 @@
/**
* @file l3gd20.cpp
* Driver for the ST L3GD20 MEMS gyro connected via SPI.
+ *
+ * Note: With the exception of the self-test feature, the ST L3G4200D is
+ * also supported by this driver.
*/
#include <nuttx/config.h>
@@ -89,9 +92,11 @@ static const int ERROR = -1;
#define ADDR_WHO_AM_I 0x0F
#define WHO_I_AM_H 0xD7
#define WHO_I_AM 0xD4
+#define WHO_I_AM_L3G4200D 0xD3 /* for L3G4200D */
#define ADDR_CTRL_REG1 0x20
#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
+
/* keep lowpass low to avoid noise issues */
#define RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
#define RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
@@ -166,9 +171,14 @@ static const int ERROR = -1;
#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
#define L3GD20_DEFAULT_RATE 760
+#define L3G4200D_DEFAULT_RATE 800
#define L3GD20_DEFAULT_RANGE_DPS 2000
#define L3GD20_DEFAULT_FILTER_FREQ 30
+#ifndef SENSOR_BOARD_ROTATION_DEFAULT
+#define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG
+#endif
+
extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); }
class L3GD20 : public device::SPI
@@ -216,6 +226,9 @@ private:
math::LowPassFilter2p _gyro_filter_y;
math::LowPassFilter2p _gyro_filter_z;
+ /* true if an L3G4200D is detected */
+ bool _is_l3g4200d;
+
/**
* Start automatic measurement.
*/
@@ -324,14 +337,15 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) :
_gyro_topic(-1),
_class_instance(-1),
_current_rate(0),
- _orientation(SENSOR_BOARD_ROTATION_270_DEG),
+ _orientation(SENSOR_BOARD_ROTATION_DEFAULT),
_read(0),
_sample_perf(perf_alloc(PC_ELAPSED, "l3gd20_read")),
_reschedules(perf_alloc(PC_COUNT, "l3gd20_reschedules")),
_errors(perf_alloc(PC_COUNT, "l3gd20_errors")),
_gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
_gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
- _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ)
+ _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ),
+ _is_l3g4200d(false)
{
// enable debug() calls
_debug_enabled = true;
@@ -413,14 +427,7 @@ L3GD20::probe()
/* verify that the device is attached and functioning, accept L3GD20 and L3GD20H */
if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
- #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #elif CONFIG_ARCH_BOARD_PX4FMU_V2
- _orientation = SENSOR_BOARD_ROTATION_270_DEG;
- #else
- #error This driver needs a board selection, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
- #endif
-
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
success = true;
}
@@ -430,6 +437,13 @@ L3GD20::probe()
success = true;
}
+ /* Detect the L3G4200D used on AeroCore */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM_L3G4200D) {
+ _is_l3g4200d = true;
+ _orientation = SENSOR_BOARD_ROTATION_DEFAULT;
+ success = true;
+ }
+
if (success)
return OK;
@@ -502,6 +516,9 @@ L3GD20::ioctl(struct file *filp, int cmd, unsigned long arg)
/* set default/max polling rate */
case SENSOR_POLLRATE_MAX:
case SENSOR_POLLRATE_DEFAULT:
+ if (_is_l3g4200d) {
+ return ioctl(filp, SENSORIOCSPOLLRATE, L3G4200D_DEFAULT_RATE);
+ }
return ioctl(filp, SENSORIOCSPOLLRATE, L3GD20_DEFAULT_RATE);
/* adjust to a legal polling interval in Hz */
@@ -683,23 +700,26 @@ L3GD20::set_samplerate(unsigned frequency)
uint8_t bits = REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
if (frequency == 0)
- frequency = 760;
+ frequency = _is_l3g4200d ? 800 : 760;
- /* use limits good for H or non-H models */
+ /*
+ * Use limits good for H or non-H models. Rates are slightly different
+ * for L3G4200D part but register settings are the same.
+ */
if (frequency <= 100) {
- _current_rate = 95;
+ _current_rate = _is_l3g4200d ? 100 : 95;
bits |= RATE_95HZ_LP_25HZ;
} else if (frequency <= 200) {
- _current_rate = 190;
+ _current_rate = _is_l3g4200d ? 200 : 190;
bits |= RATE_190HZ_LP_50HZ;
} else if (frequency <= 400) {
- _current_rate = 380;
+ _current_rate = _is_l3g4200d ? 400 : 380;
bits |= RATE_380HZ_LP_50HZ;
} else if (frequency <= 800) {
- _current_rate = 760;
+ _current_rate = _is_l3g4200d ? 800 : 760;
bits |= RATE_760HZ_LP_50HZ;
} else {
return -EINVAL;
@@ -772,7 +792,7 @@ L3GD20::reset()
* callback fast enough to not miss data. */
write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_BYPASS_MODE);
- set_samplerate(0); // 760Hz
+ set_samplerate(0); // 760Hz or 800Hz
set_range(L3GD20_DEFAULT_RANGE_DPS);
set_driver_lowpass_filter(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ);
@@ -971,7 +991,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new L3GD20(1 /* SPI bus 1 */, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
+ g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO);
if (g_dev == nullptr)
goto fail;
diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp
index 4dee7649b..4ca8b5e42 100644
--- a/src/drivers/lsm303d/lsm303d.cpp
+++ b/src/drivers/lsm303d/lsm303d.cpp
@@ -1793,7 +1793,7 @@ start()
errx(0, "already started");
/* create the driver */
- g_dev = new LSM303D(1 /* SPI dev 1 */, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
+ g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG);
if (g_dev == nullptr) {
warnx("failed instantiating LSM303D obj");
diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp
index 3cb9abc49..5954c40da 100644
--- a/src/drivers/mkblctrl/mkblctrl.cpp
+++ b/src/drivers/mkblctrl/mkblctrl.cpp
@@ -92,8 +92,20 @@
#define MOTOR_SPINUP_COUNTER 30
#define ESC_UORB_PUBLISH_DELAY 500000
-
-
+struct MotorData_t {
+ unsigned int Version; // the version of the BL (0 = old)
+ unsigned int SetPoint; // written by attitude controller
+ unsigned int SetPointLowerBits; // for higher Resolution of new BLs
+ float SetPoint_PX4; // Values from PX4
+ unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
+ unsigned int ReadMode; // select data to read
+ unsigned short RawPwmValue; // length of PWM pulse
+ // the following bytes must be exactly in that order!
+ unsigned int Current; // in 0.1 A steps, read back from BL
+ unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
+ unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
+ unsigned int RoundCount;
+};
class MK : public device::I2C
{
@@ -154,8 +166,10 @@ private:
actuator_controls_s _controls;
+ MotorData_t Motor[MAX_MOTORS];
+
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
@@ -195,24 +209,6 @@ const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0};
int addrTranslator[] = {0, 0, 0, 0, 0, 0, 0, 0};
-struct MotorData_t {
- unsigned int Version; // the version of the BL (0 = old)
- unsigned int SetPoint; // written by attitude controller
- unsigned int SetPointLowerBits; // for higher Resolution of new BLs
- float SetPoint_PX4; // Values from PX4
- unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present
- unsigned int ReadMode; // select data to read
- unsigned short RawPwmValue; // length of PWM pulse
- // the following bytes must be exactly in that order!
- unsigned int Current; // in 0.1 A steps, read back from BL
- unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit
- unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in
- unsigned int RoundCount;
-};
-
-MotorData_t Motor[MAX_MOTORS];
-
-
namespace
{
diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp
index ac75682c4..321fdd173 100644
--- a/src/drivers/mpu6000/mpu6000.cpp
+++ b/src/drivers/mpu6000/mpu6000.cpp
@@ -1380,7 +1380,6 @@ MPU6000_gyro::init()
_gyro_class_instance = register_class_devname(GYRO_DEVICE_PATH);
-out:
return ret;
}
diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp
index 0ef056273..1ce93aeea 100644
--- a/src/drivers/ms5611/ms5611.cpp
+++ b/src/drivers/ms5611/ms5611.cpp
@@ -526,6 +526,7 @@ void
MS5611::cycle()
{
int ret;
+ unsigned dummy;
/* collection phase? */
if (_collect_phase) {
@@ -542,6 +543,8 @@ MS5611::cycle()
} else {
//log("collection error %d", ret);
}
+ /* issue a reset command to the sensor */
+ _interface->ioctl(IOCTL_RESET, dummy);
/* reset the collection state machine and try again */
start_cycle();
return;
@@ -573,6 +576,8 @@ MS5611::cycle()
ret = measure();
if (ret != OK) {
//log("measure error %d", ret);
+ /* issue a reset command to the sensor */
+ _interface->ioctl(IOCTL_RESET, dummy);
/* reset the collection state machine and try again */
start_cycle();
return;
@@ -748,8 +753,8 @@ MS5611::print_info()
printf("TEMP: %d\n", _TEMP);
printf("SENS: %lld\n", _SENS);
printf("OFF: %lld\n", _OFF);
- printf("P: %.3f\n", _P);
- printf("T: %.3f\n", _T);
+ printf("P: %.3f\n", (double)_P);
+ printf("T: %.3f\n", (double)_T);
printf("MSL pressure: %10.4f\n", (double)(_msl_pressure / 100.f));
printf("factory_setup %u\n", _prom.factory_setup);
diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp
index 26216e840..8759d16a1 100644
--- a/src/drivers/ms5611/ms5611_spi.cpp
+++ b/src/drivers/ms5611/ms5611_spi.cpp
@@ -117,7 +117,7 @@ private:
device::Device *
MS5611_spi_interface(ms5611::prom_u &prom_buf)
{
- return new MS5611_SPI(1 /* XXX MAGIC NUMBER */, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
+ return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf);
}
MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) :
diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp
index 7258d5f9e..8a4bfa18c 100644
--- a/src/drivers/px4fmu/fmu.cpp
+++ b/src/drivers/px4fmu/fmu.cpp
@@ -92,6 +92,7 @@ public:
MODE_2PWM,
MODE_4PWM,
MODE_6PWM,
+ MODE_8PWM,
};
PX4FMU();
virtual ~PX4FMU();
@@ -113,6 +114,9 @@ private:
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
static const unsigned _max_actuators = 6;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ static const unsigned _max_actuators = 8;
+#endif
Mode _mode;
unsigned _pwm_default_rate;
@@ -120,19 +124,25 @@ private:
uint32_t _pwm_alt_rate_channels;
unsigned _current_update_rate;
int _task;
- int _t_actuators;
- int _t_actuator_armed;
- orb_advert_t _t_outputs;
+ int _armed_sub;
+ orb_advert_t _outputs_pub;
+ actuator_armed_s _armed;
unsigned _num_outputs;
bool _primary_pwm_device;
volatile bool _task_should_exit;
- bool _armed;
+ bool _servo_armed;
bool _pwm_on;
MixerGroup *_mixers;
- actuator_controls_s _controls;
+ uint32_t _groups_required;
+ uint32_t _groups_subscribed;
+ int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS];
+ actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS];
+ orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS];
+ pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS];
+ unsigned _poll_fds_num;
pwm_limit_t _pwm_limit;
uint16_t _failsafe_pwm[_max_actuators];
@@ -143,13 +153,13 @@ private:
unsigned _num_disarmed_set;
static void task_main_trampoline(int argc, char *argv[]);
- void task_main() __attribute__((noreturn));
+ void task_main();
static int control_callback(uintptr_t handle,
uint8_t control_group,
uint8_t control_index,
float &input);
-
+ void subscribe();
int set_pwm_rate(unsigned rate_map, unsigned default_rate, unsigned alt_rate);
int pwm_ioctl(file *filp, int cmd, unsigned long arg);
@@ -197,6 +207,20 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
{GPIO_VDD_5V_HIPOWER_OC, 0, 0},
{GPIO_VDD_5V_PERIPH_OC, 0, 0},
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ /* AeroCore breaks out User GPIOs on J11 */
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0},
+ {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, 0},
+ {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, 0},
+ {GPIO_GPIO8_INPUT, GPIO_GPIO8_OUTPUT, 0},
+ {GPIO_GPIO9_INPUT, GPIO_GPIO9_OUTPUT, 0},
+ {GPIO_GPIO10_INPUT, GPIO_GPIO10_OUTPUT, 0},
+ {GPIO_GPIO11_INPUT, GPIO_GPIO11_OUTPUT, 0},
+#endif
};
const unsigned PX4FMU::_ngpio = sizeof(PX4FMU::_gpio_tab) / sizeof(PX4FMU::_gpio_tab[0]);
@@ -216,15 +240,18 @@ PX4FMU::PX4FMU() :
_pwm_alt_rate_channels(0),
_current_update_rate(0),
_task(-1),
- _t_actuators(-1),
- _t_actuator_armed(-1),
- _t_outputs(0),
+ _control_subs({-1}),
+ _poll_fds_num(0),
+ _armed_sub(-1),
+ _outputs_pub(-1),
_num_outputs(0),
_primary_pwm_device(false),
_task_should_exit(false),
- _armed(false),
+ _servo_armed(false),
_pwm_on(false),
_mixers(nullptr),
+ _groups_required(0),
+ _groups_subscribed(0),
_failsafe_pwm({0}),
_disarmed_pwm({0}),
_num_failsafe_set(0),
@@ -235,6 +262,14 @@ PX4FMU::PX4FMU() :
_max_pwm[i] = PWM_DEFAULT_MAX;
}
+ _control_topics[0] = ORB_ID(actuator_controls_0);
+ _control_topics[1] = ORB_ID(actuator_controls_1);
+ _control_topics[2] = ORB_ID(actuator_controls_2);
+ _control_topics[3] = ORB_ID(actuator_controls_3);
+
+ memset(_controls, 0, sizeof(_controls));
+ memset(_poll_fds, 0, sizeof(_poll_fds));
+
_debug_enabled = true;
}
@@ -365,6 +400,20 @@ PX4FMU::set_mode(Mode mode)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM: // AeroCore PWMs as 8 PWM outs
+ debug("MODE_8PWM");
+ /* default output rates */
+ _pwm_default_rate = 50;
+ _pwm_alt_rate = 50;
+ _pwm_alt_rate_channels = 0;
+
+ /* XXX magic numbers */
+ up_pwm_servo_init(0xff);
+ set_pwm_rate(_pwm_alt_rate_channels, _pwm_default_rate, _pwm_alt_rate);
+ break;
+#endif
+
case MODE_NONE:
debug("MODE_NONE");
@@ -448,32 +497,42 @@ PX4FMU::set_pwm_alt_channels(uint32_t channels)
}
void
+PX4FMU::subscribe()
+{
+ /* subscribe/unsubscribe to required actuator control groups */
+ uint32_t sub_groups = _groups_required & ~_groups_subscribed;
+ uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
+ _poll_fds_num = 0;
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (sub_groups & (1 << i)) {
+ warnx("subscribe to actuator_controls_%d", i);
+ _control_subs[i] = orb_subscribe(_control_topics[i]);
+ }
+ if (unsub_groups & (1 << i)) {
+ warnx("unsubscribe from actuator_controls_%d", i);
+ ::close(_control_subs[i]);
+ _control_subs[i] = -1;
+ }
+
+ if (_control_subs[i] > 0) {
+ _poll_fds[_poll_fds_num].fd = _control_subs[i];
+ _poll_fds[_poll_fds_num].events = POLLIN;
+ _poll_fds_num++;
+ }
+ }
+}
+
+void
PX4FMU::task_main()
{
- /*
- * Subscribe to the appropriate PWM output topic based on whether we are the
- * primary PWM output or not.
- */
- _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS :
- ORB_ID(actuator_controls_1));
/* force a reset of the update rate */
_current_update_rate = 0;
- _t_actuator_armed = orb_subscribe(ORB_ID(actuator_armed));
- orb_set_interval(_t_actuator_armed, 200); /* 5Hz update rate */
+ _armed_sub = orb_subscribe(ORB_ID(actuator_armed));
/* advertise the mixed control outputs */
actuator_outputs_s outputs;
memset(&outputs, 0, sizeof(outputs));
- /* advertise the mixed control outputs */
- _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1),
- &outputs);
-
- pollfd fds[2];
- fds[0].fd = _t_actuators;
- fds[0].events = POLLIN;
- fds[1].fd = _t_actuator_armed;
- fds[1].events = POLLIN;
#ifdef HRT_PPM_CHANNEL
// rc input, published to ORB
@@ -491,6 +550,12 @@ PX4FMU::task_main()
/* loop until killed */
while (!_task_should_exit) {
+ if (_groups_subscribed != _groups_required) {
+ subscribe();
+ _groups_subscribed = _groups_required;
+ /* force setting update rate */
+ _current_update_rate = 0;
+ }
/*
* Adjust actuator topic update rate to keep up with
@@ -515,20 +580,23 @@ PX4FMU::task_main()
}
debug("adjusted actuator update interval to %ums", update_rate_in_ms);
- orb_set_interval(_t_actuators, update_rate_in_ms);
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs[i] > 0) {
+ orb_set_interval(_control_subs[i], update_rate_in_ms);
+ }
+ }
// set to current max rate, even if we are actually checking slower/faster
_current_update_rate = max_rate;
}
/* sleep waiting for data, stopping to check for PPM
- * input at 100Hz */
- int ret = ::poll(&fds[0], 2, CONTROL_INPUT_DROP_LIMIT_MS);
+ * input at 50Hz */
+ int ret = ::poll(_poll_fds, _poll_fds_num, CONTROL_INPUT_DROP_LIMIT_MS);
/* this would be bad... */
if (ret < 0) {
log("poll error %d", errno);
- usleep(1000000);
continue;
} else if (ret == 0) {
@@ -537,89 +605,100 @@ PX4FMU::task_main()
} else {
- /* do we have a control update? */
- if (fds[0].revents & POLLIN) {
+ /* get controls for required topics */
+ unsigned poll_id = 0;
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs[i] > 0) {
+ if (_poll_fds[poll_id].revents & POLLIN) {
+ orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
+ }
+ poll_id++;
+ }
+ }
- /* get controls - must always do this to avoid spinning */
- orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls);
+ /* can we mix? */
+ if (_mixers != nullptr) {
- /* can we mix? */
- if (_mixers != nullptr) {
+ unsigned num_outputs;
- unsigned num_outputs;
+ switch (_mode) {
+ case MODE_2PWM:
+ num_outputs = 2;
+ break;
- switch (_mode) {
- case MODE_2PWM:
- num_outputs = 2;
- break;
+ case MODE_4PWM:
+ num_outputs = 4;
+ break;
- case MODE_4PWM:
- num_outputs = 4;
- break;
+ case MODE_6PWM:
+ num_outputs = 6;
+ break;
- case MODE_6PWM:
- num_outputs = 6;
- break;
+ case MODE_8PWM:
+ num_outputs = 8;
+ break;
+ default:
+ num_outputs = 0;
+ break;
+ }
- default:
- num_outputs = 0;
- break;
+ /* do mixing */
+ outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
+ outputs.timestamp = hrt_absolute_time();
+
+ /* iterate actuators */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ /* last resort: catch NaN and INF */
+ if ((i >= outputs.noutputs) ||
+ !isfinite(outputs.output[i])) {
+ /*
+ * Value is NaN, INF or out of band - set to the minimum value.
+ * This will be clearly visible on the servo status and will limit the risk of accidentally
+ * spinning motors. It would be deadly in flight.
+ */
+ outputs.output[i] = -1.0f;
}
+ }
- /* do mixing */
- outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs);
- outputs.timestamp = hrt_absolute_time();
-
- /* iterate actuators */
- for (unsigned i = 0; i < num_outputs; i++) {
- /* last resort: catch NaN, INF and out-of-band errors */
- if (i >= outputs.noutputs ||
- !isfinite(outputs.output[i]) ||
- outputs.output[i] < -1.0f ||
- outputs.output[i] > 1.0f) {
- /*
- * Value is NaN, INF or out of band - set to the minimum value.
- * This will be clearly visible on the servo status and will limit the risk of accidentally
- * spinning motors. It would be deadly in flight.
- */
- outputs.output[i] = -1.0f;
- }
- }
+ uint16_t pwm_limited[num_outputs];
- uint16_t pwm_limited[num_outputs];
+ /* the PWM limit call takes care of out of band errors and constrains */
+ pwm_limit_calc(_servo_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
- pwm_limit_calc(_armed, num_outputs, _disarmed_pwm, _min_pwm, _max_pwm, outputs.output, pwm_limited, &_pwm_limit);
+ /* output to the servos */
+ for (unsigned i = 0; i < num_outputs; i++) {
+ up_pwm_servo_set(i, pwm_limited[i]);
+ }
- /* output to the servos */
- for (unsigned i = 0; i < num_outputs; i++) {
- up_pwm_servo_set(i, pwm_limited[i]);
- }
+ /* publish mixed control outputs */
+ if (_outputs_pub < 0) {
+ _outputs_pub = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), &outputs);
+ } else {
- /* and publish for anyone that cares to see */
- orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs);
+ orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _outputs_pub, &outputs);
}
}
+ }
- /* how about an arming update? */
- if (fds[1].revents & POLLIN) {
- actuator_armed_s aa;
+ /* check arming state */
+ bool updated = false;
+ orb_check(_armed_sub, &updated);
- /* get new value */
- orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &aa);
+ if (updated) {
+ orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed);
- /* update the armed status and check that we're not locked down */
- bool set_armed = aa.armed && !aa.lockdown;
+ /* update the armed status and check that we're not locked down */
+ bool set_armed = _armed.armed && !_armed.lockdown;
- if (_armed != set_armed)
- _armed = set_armed;
+ if (_servo_armed != set_armed)
+ _servo_armed = set_armed;
- /* update PWM status if armed or if disarmed PWM values are set */
- bool pwm_on = (aa.armed || _num_disarmed_set > 0);
+ /* update PWM status if armed or if disarmed PWM values are set */
+ bool pwm_on = (_armed.armed || _num_disarmed_set > 0);
- if (_pwm_on != pwm_on) {
- _pwm_on = pwm_on;
- up_pwm_servo_arm(pwm_on);
- }
+ if (_pwm_on != pwm_on) {
+ _pwm_on = pwm_on;
+ up_pwm_servo_arm(pwm_on);
}
}
@@ -661,8 +740,13 @@ PX4FMU::task_main()
}
- ::close(_t_actuators);
- ::close(_t_actuator_armed);
+ for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
+ if (_control_subs > 0) {
+ ::close(_control_subs[i]);
+ _control_subs[i] = -1;
+ }
+ }
+ ::close(_armed_sub);
/* make sure servos are off */
up_pwm_servo_deinit();
@@ -684,7 +768,7 @@ PX4FMU::control_callback(uintptr_t handle,
{
const actuator_controls_s *controls = (actuator_controls_s *)handle;
- input = controls->control[control_index];
+ input = controls[control_group].control[control_index];
return 0;
}
@@ -707,6 +791,9 @@ PX4FMU::ioctl(file *filp, int cmd, unsigned long arg)
case MODE_2PWM:
case MODE_4PWM:
case MODE_6PWM:
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+#endif
ret = pwm_ioctl(filp, cmd, arg);
break;
@@ -936,6 +1023,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
}
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_SET(7):
+ case PWM_SERVO_SET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_SET(5):
case PWM_SERVO_SET(4):
if (_mode < MODE_6PWM) {
@@ -963,6 +1059,15 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
break;
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET(7):
+ case PWM_SERVO_GET(6):
+ if (_mode < MODE_8PWM) {
+ ret = -EINVAL;
+ break;
+ }
+#endif
+
case PWM_SERVO_GET(5):
case PWM_SERVO_GET(4):
if (_mode < MODE_6PWM) {
@@ -990,12 +1095,22 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
case PWM_SERVO_GET_RATEGROUP(3):
case PWM_SERVO_GET_RATEGROUP(4):
case PWM_SERVO_GET_RATEGROUP(5):
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case PWM_SERVO_GET_RATEGROUP(6):
+ case PWM_SERVO_GET_RATEGROUP(7):
+#endif
*(uint32_t *)arg = up_pwm_servo_get_rate_group(cmd - PWM_SERVO_GET_RATEGROUP(0));
break;
case PWM_SERVO_GET_COUNT:
case MIXERIOCGETOUTPUTCOUNT:
switch (_mode) {
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ case MODE_8PWM:
+ *(unsigned *)arg = 8;
+ break;
+#endif
+
case MODE_6PWM:
*(unsigned *)arg = 6;
break;
@@ -1041,6 +1156,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
set_mode(MODE_6PWM);
break;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ case 8:
+ set_mode(MODE_8PWM);
+ break;
+#endif
default:
ret = -EINVAL;
@@ -1053,6 +1173,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
if (_mixers != nullptr) {
delete _mixers;
_mixers = nullptr;
+ _groups_required = 0;
}
break;
@@ -1061,18 +1182,20 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
mixer_simple_s *mixinfo = (mixer_simple_s *)arg;
SimpleMixer *mixer = new SimpleMixer(control_callback,
- (uintptr_t)&_controls, mixinfo);
+ (uintptr_t)_controls, mixinfo);
if (mixer->check()) {
delete mixer;
+ _groups_required = 0;
ret = -EINVAL;
} else {
if (_mixers == nullptr)
_mixers = new MixerGroup(control_callback,
- (uintptr_t)&_controls);
+ (uintptr_t)_controls);
_mixers->add_mixer(mixer);
+ _mixers->groups_required(_groups_required);
}
break;
@@ -1083,9 +1206,10 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
unsigned buflen = strnlen(buf, 1024);
if (_mixers == nullptr)
- _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls);
+ _mixers = new MixerGroup(control_callback, (uintptr_t)_controls);
if (_mixers == nullptr) {
+ _groups_required = 0;
ret = -ENOMEM;
} else {
@@ -1096,7 +1220,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg)
debug("mixer load failed with %d", ret);
delete _mixers;
_mixers = nullptr;
+ _groups_required = 0;
ret = -EINVAL;
+ } else {
+
+ _mixers->groups_required(_groups_required);
}
}
@@ -1123,10 +1251,17 @@ PX4FMU::write(file *filp, const char *buffer, size_t len)
unsigned count = len / 2;
uint16_t values[6];
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ if (count > 8) {
+ // we have at most 8 outputs
+ count = 8;
+ }
+#else
if (count > 6) {
// we have at most 6 outputs
count = 6;
}
+#endif
// allow for misaligned values
memcpy(values, buffer, count * 2);
@@ -1401,6 +1536,9 @@ fmu_new_mode(PortMode new_mode)
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
servo_mode = PX4FMU::MODE_6PWM;
#endif
+#if defined(CONFIG_ARCH_BOARD_AEROCORE)
+ servo_mode = PX4FMU::MODE_8PWM;
+#endif
break;
/* mixed modes supported on v1 board only */
@@ -1718,7 +1856,7 @@ fmu_main(int argc, char *argv[])
fprintf(stderr, "FMU: unrecognised command %s, try:\n", verb);
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio, test\n");
-#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
+#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2) || defined(CONFIG_ARCH_BOARD_AEROCORE)
fprintf(stderr, " mode_gpio, mode_pwm, test, sensor_reset [milliseconds]\n");
#endif
exit(1);
diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk
index 05bc7a5b3..eeb59e1a1 100644
--- a/src/drivers/px4fmu/module.mk
+++ b/src/drivers/px4fmu/module.mk
@@ -4,3 +4,5 @@
MODULE_COMMAND = fmu
SRCS = fmu.cpp
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk
index 2054faa12..c14f1f783 100644
--- a/src/drivers/px4io/module.mk
+++ b/src/drivers/px4io/module.mk
@@ -44,3 +44,5 @@ SRCS = px4io.cpp \
# XXX prune to just get UART registers
INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common
+
+MODULE_STACKSIZE = 1200
diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp
index 8458c2fdb..972f45148 100644
--- a/src/drivers/px4io/px4io.cpp
+++ b/src/drivers/px4io/px4io.cpp
@@ -529,6 +529,11 @@ PX4IO::~PX4IO()
if (_interface != nullptr)
delete _interface;
+ /* deallocate perfs */
+ perf_free(_perf_update);
+ perf_free(_perf_write);
+ perf_free(_perf_chan_count);
+
g_dev = nullptr;
}
@@ -576,8 +581,10 @@ PX4IO::init()
ASSERT(_task == -1);
sys_restart_param = param_find("SYS_RESTART_TYPE");
- /* Indicate restart type is unknown */
- param_set(sys_restart_param, &sys_restart_val);
+ if (sys_restart_param != PARAM_INVALID) {
+ /* Indicate restart type is unknown */
+ param_set(sys_restart_param, &sys_restart_val);
+ }
/* do regular cdev init */
ret = CDev::init();
@@ -683,6 +690,25 @@ PX4IO::init()
/* send command to arm system via command API */
vehicle_command_s cmd;
+ /* send this to itself */
+ param_t sys_id_param = param_find("MAV_SYS_ID");
+ param_t comp_id_param = param_find("MAV_COMP_ID");
+
+ int32_t sys_id;
+ int32_t comp_id;
+
+ if (param_get(sys_id_param, &sys_id)) {
+ errx(1, "PRM SYSID");
+ }
+
+ if (param_get(comp_id_param, &comp_id)) {
+ errx(1, "PRM CMPID");
+ }
+
+ cmd.target_system = sys_id;
+ cmd.target_component = comp_id;
+ cmd.source_system = sys_id;
+ cmd.source_component = comp_id;
/* request arming */
cmd.param1 = 1.0f;
cmd.param2 = 0;
@@ -692,10 +718,7 @@ PX4IO::init()
cmd.param6 = 0;
cmd.param7 = 0;
cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM;
- // cmd.target_system = status.system_id;
- // cmd.target_component = status.component_id;
- // cmd.source_system = status.system_id;
- // cmd.source_component = status.component_id;
+
/* ask to confirm command */
cmd.confirmation = 1;
@@ -773,7 +796,12 @@ PX4IO::init()
}
/* start the IO interface task */
- _task = task_create("px4io", SCHED_PRIORITY_ACTUATOR_OUTPUTS, 2048, (main_t)&PX4IO::task_main_trampoline, nullptr);
+ _task = task_spawn_cmd("px4io",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_ACTUATOR_OUTPUTS,
+ 2000,
+ (main_t)&PX4IO::task_main_trampoline,
+ nullptr);
if (_task < 0) {
debug("task start failed: %d", errno);
@@ -968,13 +996,17 @@ PX4IO::task_main()
int32_t failsafe_param_val;
param_t failsafe_param = param_find("RC_FAILS_THR");
- if (failsafe_param > 0) {
+ if (failsafe_param != PARAM_INVALID) {
param_get(failsafe_param, &failsafe_param_val);
- uint16_t failsafe_thr = failsafe_param_val;
- pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
- if (pret != OK) {
- log("failsafe upload failed");
+
+ if (failsafe_param_val > 0) {
+
+ uint16_t failsafe_thr = failsafe_param_val;
+ pret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RC_THR_FAILSAFE_US, &failsafe_thr, 1);
+ if (pret != OK) {
+ log("failsafe upload failed, FS: %d us", (int)failsafe_thr);
+ }
}
}
@@ -1432,7 +1464,7 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
/* we don't have the status bits, so input_source has to be set elsewhere */
input_rc.input_source = RC_INPUT_SOURCE_UNKNOWN;
- static const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
+ const unsigned prolog = (PX4IO_P_RAW_RC_BASE - PX4IO_P_RAW_RC_COUNT);
uint16_t regs[RC_INPUT_MAX_CHANNELS + prolog];
/*
@@ -1440,8 +1472,6 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*
* This should be the common case (9 channel R/C control being a reasonable upper bound).
*/
- input_rc.timestamp_publication = hrt_absolute_time();
-
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_COUNT, &regs[0], prolog + 9);
if (ret != OK)
@@ -1453,23 +1483,38 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
*/
channel_count = regs[PX4IO_P_RAW_RC_COUNT];
- if (channel_count != _rc_chan_count)
+ /* limit the channel count */
+ if (channel_count > RC_INPUT_MAX_CHANNELS) {
+ channel_count = RC_INPUT_MAX_CHANNELS;
+ }
+
+ /* count channel count changes to identify signal integrity issues */
+ if (channel_count != _rc_chan_count) {
perf_count(_perf_chan_count);
+ }
_rc_chan_count = channel_count;
+ input_rc.timestamp_publication = hrt_absolute_time();
+
input_rc.rc_ppm_frame_length = regs[PX4IO_P_RAW_RC_DATA];
input_rc.rssi = regs[PX4IO_P_RAW_RC_NRSSI];
input_rc.rc_failsafe = (regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_FAILSAFE);
+ input_rc.rc_lost = !(regs[PX4IO_P_RAW_RC_FLAGS] & PX4IO_P_RAW_RC_FLAGS_RC_OK);
input_rc.rc_lost_frame_count = regs[PX4IO_P_RAW_LOST_FRAME_COUNT];
input_rc.rc_total_frame_count = regs[PX4IO_P_RAW_FRAME_COUNT];
+ input_rc.channel_count = channel_count;
/* rc_lost has to be set before the call to this function */
- if (!input_rc.rc_lost && !input_rc.rc_failsafe)
+ if (!input_rc.rc_lost && !input_rc.rc_failsafe) {
_rc_last_valid = input_rc.timestamp_publication;
+ }
input_rc.timestamp_last_signal = _rc_last_valid;
+ /* FIELDS NOT SET HERE */
+ /* input_rc.input_source is set after this call XXX we might want to mirror the flags in the RC struct */
+
if (channel_count > 9) {
ret = io_reg_get(PX4IO_PAGE_RAW_RC_INPUT, PX4IO_P_RAW_RC_BASE + 9, &regs[prolog + 9], channel_count - 9);
@@ -1477,8 +1522,10 @@ PX4IO::io_get_raw_rc_input(rc_input_values &input_rc)
return ret;
}
- input_rc.channel_count = channel_count;
- memcpy(input_rc.values, &regs[prolog], channel_count * 2);
+ /* last thing set are the actual channel values as 16 bit values */
+ for (unsigned i = 0; i < channel_count; i++) {
+ input_rc.values[i] = regs[prolog + i];
+ }
return ret;
}
diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp
index 43318ca84..3b210ac59 100644
--- a/src/drivers/px4io/px4io_serial.cpp
+++ b/src/drivers/px4io/px4io_serial.cpp
@@ -639,7 +639,7 @@ PX4IO_serial::_do_interrupt()
if (_rx_dma_status == _dma_status_waiting) {
/* verify that the received packet is complete */
- unsigned length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
+ int length = sizeof(_dma_buffer) - stm32_dmaresidual(_rx_dma);
if ((length < 1) || (length < PKT_SIZE(_dma_buffer))) {
perf_count(_pc_badidle);
diff --git a/src/drivers/sf0x/sf0x.cpp b/src/drivers/sf0x/sf0x.cpp
index a0cf98340..9109af14f 100644
--- a/src/drivers/sf0x/sf0x.cpp
+++ b/src/drivers/sf0x/sf0x.cpp
@@ -254,9 +254,6 @@ SF0X::~SF0X()
int
SF0X::init()
{
- int ret = ERROR;
- unsigned i = 0;
-
/* do regular cdev init */
if (CDev::init() != OK) {
goto out;
@@ -594,7 +591,7 @@ SF0X::collect()
valid = false;
/* wipe out partially read content from last cycle(s), check for dot */
- for (int i = 0; i < (lend - 2); i++) {
+ for (unsigned i = 0; i < (lend - 2); i++) {
if (_linebuf[i] == '\n') {
char buf[sizeof(_linebuf)];
memcpy(buf, &_linebuf[i+1], (lend + 1) - (i + 1));
@@ -795,7 +792,7 @@ const int ERROR = -1;
SF0X *g_dev;
-void start();
+void start(const char *port);
void stop();
void test();
void reset();
diff --git a/src/drivers/stm32/adc/adc.cpp b/src/drivers/stm32/adc/adc.cpp
index 3a60d2cae..aa0dca60c 100644
--- a/src/drivers/stm32/adc/adc.cpp
+++ b/src/drivers/stm32/adc/adc.cpp
@@ -145,7 +145,7 @@ private:
ADC::ADC(uint32_t channels) :
CDev("adc", ADC_DEVICE_PATH),
- _sample_perf(perf_alloc(PC_ELAPSED, "ADC samples")),
+ _sample_perf(perf_alloc(PC_ELAPSED, "adc_samples")),
_channel_count(0),
_samples(nullptr),
_to_system_power(0)
@@ -419,6 +419,10 @@ adc_main(int argc, char *argv[])
g_adc = new ADC((1 << 2) | (1 << 3) | (1 << 4) |
(1 << 10) | (1 << 11) | (1 << 12) | (1 << 13) | (1 << 14) | (1 << 15));
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ /* XXX this hardcodes the default channel set for AeroCore - should be configurable */
+ g_adc = new ADC((1 << 10) | (1 << 11) | (1 << 12) | (1 << 13));
+#endif
if (g_adc == nullptr)
errx(1, "couldn't allocate the ADC driver");
diff --git a/src/drivers/stm32/drv_hrt.c b/src/drivers/stm32/drv_hrt.c
index b7c9b89a4..281f918d7 100644
--- a/src/drivers/stm32/drv_hrt.c
+++ b/src/drivers/stm32/drv_hrt.c
@@ -94,7 +94,7 @@
#elif HRT_TIMER == 3
# define HRT_TIMER_BASE STM32_TIM3_BASE
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
-# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
+# define HRT_TIMER_POWER_BIT RCC_APB1ENR_TIM3EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
# if CONFIG_STM32_TIM3
@@ -141,7 +141,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
-# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM10_CLKIN
# if CONFIG_STM32_TIM10
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
# endif
@@ -150,7 +150,7 @@
# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
-# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
+# define HRT_TIMER_CLOCK STM32_APB2_TIM11_CLKIN
# if CONFIG_STM32_TIM11
# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
# endif
@@ -354,6 +354,9 @@ __EXPORT uint16_t ppm_frame_length = 0;
__EXPORT unsigned ppm_decoded_channels = 0;
__EXPORT uint64_t ppm_last_valid_decode = 0;
+#define PPM_DEBUG 0
+
+#if PPM_DEBUG
/* PPM edge history */
__EXPORT uint16_t ppm_edge_history[32];
unsigned ppm_edge_next;
@@ -361,6 +364,7 @@ unsigned ppm_edge_next;
/* PPM pulse history */
__EXPORT uint16_t ppm_pulse_history[32];
unsigned ppm_pulse_next;
+#endif
static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
@@ -455,10 +459,12 @@ hrt_ppm_decode(uint32_t status)
/* how long since the last edge? - this handles counter wrapping implicitely. */
width = count - ppm.last_edge;
+#if PPM_DEBUG
ppm_edge_history[ppm_edge_next++] = width;
if (ppm_edge_next >= 32)
ppm_edge_next = 0;
+#endif
/*
* if this looks like a start pulse, then push the last set of values
@@ -546,10 +552,12 @@ hrt_ppm_decode(uint32_t status)
interval = count - ppm.last_mark;
ppm.last_mark = count;
+#if PPM_DEBUG
ppm_pulse_history[ppm_pulse_next++] = interval;
if (ppm_pulse_next >= 32)
ppm_pulse_next = 0;
+#endif
/* if the mark-mark timing is out of bounds, abandon the frame */
if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk
index d2c48934f..a2a9eb113 100644
--- a/src/examples/fixedwing_control/module.mk
+++ b/src/examples/fixedwing_control/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = ex_fixedwing_control
SRCS = main.c \
params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/examples/flow_position_control/flow_position_control_main.c b/src/examples/flow_position_control/flow_position_control_main.c
deleted file mode 100644
index 391e40ac1..000000000
--- a/src/examples/flow_position_control/flow_position_control_main.c
+++ /dev/null
@@ -1,613 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file flow_position_control.c
- *
- * Optical flow position controller
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <stdbool.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <debug.h>
-#include <termios.h>
-#include <time.h>
-#include <math.h>
-#include <sys/prctl.h>
-#include <drivers/drv_hrt.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/actuator_armed.h>
-#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
-#include <uORB/topics/filtered_bottom_flow.h>
-#include <systemlib/systemlib.h>
-#include <systemlib/perf_counter.h>
-#include <systemlib/err.h>
-#include <poll.h>
-#include <mavlink/mavlink_log.h>
-
-#include "flow_position_control_params.h"
-
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-__EXPORT int flow_position_control_main(int argc, char *argv[]);
-
-/**
- * Mainloop of position controller.
- */
-static int flow_position_control_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
- exit(1);
-}
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_spawn_cmd().
- */
-int flow_position_control_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start"))
- {
- if (thread_running)
- {
- printf("flow position control already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn_cmd("flow_position_control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 6,
- 4096,
- flow_position_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop"))
- {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status"))
- {
- if (thread_running)
- printf("\tflow position control app is running\n");
- else
- printf("\tflow position control app not started\n");
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-static int
-flow_position_control_thread_main(int argc, char *argv[])
-{
- /* welcome user */
- thread_running = true;
- static int mavlink_fd;
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
- mavlink_log_info(mavlink_fd, "[fpc] started");
-
- uint32_t counter = 0;
- const float time_scale = powf(10.0f,-6.0f);
-
- /* structures */
- struct actuator_armed_s armed;
- memset(&armed, 0, sizeof(armed));
- struct vehicle_control_mode_s control_mode;
- memset(&control_mode, 0, sizeof(control_mode));
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- struct manual_control_setpoint_s manual;
- memset(&manual, 0, sizeof(manual));
- struct filtered_bottom_flow_s filtered_flow;
- memset(&filtered_flow, 0, sizeof(filtered_flow));
- struct vehicle_local_position_s local_pos;
- memset(&local_pos, 0, sizeof(local_pos));
- struct vehicle_bodyframe_speed_setpoint_s speed_sp;
- memset(&speed_sp, 0, sizeof(speed_sp));
-
- /* subscribe to attitude, motor setpoints and system state */
- int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
- int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
- int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- int manual_control_setpoint_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
- int vehicle_local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
-
- orb_advert_t speed_sp_pub;
- bool speed_setpoint_adverted = false;
-
- /* parameters init*/
- struct flow_position_control_params params;
- struct flow_position_control_param_handles param_handles;
- parameters_init(&param_handles);
- parameters_update(&param_handles, &params);
-
- /* init flow sum setpoint */
- float flow_sp_sumx = 0.0f;
- float flow_sp_sumy = 0.0f;
-
- /* init yaw setpoint */
- float yaw_sp = 0.0f;
-
- /* init height setpoint */
- float height_sp = params.height_min;
-
- /* height controller states */
- bool start_phase = true;
- bool landing_initialized = false;
- float landing_thrust_start = 0.0f;
-
- /* states */
- float integrated_h_error = 0.0f;
- float last_local_pos_z = 0.0f;
- bool update_flow_sp_sumx = false;
- bool update_flow_sp_sumy = false;
- uint64_t last_time = 0.0f;
- float dt = 0.0f; // s
-
-
- /* register the perf counter */
- perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "flow_position_control_runtime");
- perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "flow_position_control_interval");
- perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "flow_position_control_err");
-
- static bool sensors_ready = false;
- static bool status_changed = false;
-
- while (!thread_should_exit)
- {
- /* wait for first attitude msg to be sure all data are available */
- if (sensors_ready)
- {
- /* polling */
- struct pollfd fds[2] = {
- { .fd = filtered_bottom_flow_sub, .events = POLLIN }, // positions from estimator
- { .fd = parameter_update_sub, .events = POLLIN }
-
- };
-
- /* wait for a position update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
-
- if (ret < 0)
- {
- /* poll error, count it in perf */
- perf_count(mc_err_perf);
- }
- else if (ret == 0)
- {
- /* no return value, ignore */
-// printf("[flow position control] no filtered flow updates\n");
- }
- else
- {
- /* parameter update available? */
- if (fds[1].revents & POLLIN)
- {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
-
- parameters_update(&param_handles, &params);
- mavlink_log_info(mavlink_fd,"[fpc] parameters updated.");
- }
-
- /* only run controller if position/speed changed */
- if (fds[0].revents & POLLIN)
- {
- perf_begin(mc_loop_perf);
-
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_control_setpoint_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- /* get a local copy of filtered bottom flow */
- orb_copy(ORB_ID(filtered_bottom_flow), filtered_bottom_flow_sub, &filtered_flow);
- /* get a local copy of local position */
- orb_copy(ORB_ID(vehicle_local_position), vehicle_local_position_sub, &local_pos);
- /* get a local copy of control mode */
- orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
-
- if (control_mode.flag_control_velocity_enabled)
- {
- float manual_pitch = manual.pitch / params.rc_scale_pitch; // 0 to 1
- float manual_roll = manual.roll / params.rc_scale_roll; // 0 to 1
- float manual_yaw = manual.yaw / params.rc_scale_yaw; // -1 to 1
-
- if(status_changed == false)
- mavlink_log_info(mavlink_fd,"[fpc] flow POSITION control engaged");
-
- status_changed = true;
-
- /* calc dt */
- if(last_time == 0)
- {
- last_time = hrt_absolute_time();
- continue;
- }
- dt = ((float) (hrt_absolute_time() - last_time)) * time_scale;
- last_time = hrt_absolute_time();
-
- /* update flow sum setpoint */
- if (update_flow_sp_sumx)
- {
- flow_sp_sumx = filtered_flow.sumx;
- update_flow_sp_sumx = false;
- }
- if (update_flow_sp_sumy)
- {
- flow_sp_sumy = filtered_flow.sumy;
- update_flow_sp_sumy = false;
- }
-
- /* calc new bodyframe speed setpoints */
- float speed_body_x = (flow_sp_sumx - filtered_flow.sumx) * params.pos_p - filtered_flow.vx * params.pos_d;
- float speed_body_y = (flow_sp_sumy - filtered_flow.sumy) * params.pos_p - filtered_flow.vy * params.pos_d;
- float speed_limit_height_factor = height_sp; // the settings are for 1 meter
-
- /* overwrite with rc input if there is any */
- if(isfinite(manual_pitch) && isfinite(manual_roll))
- {
- if(fabsf(manual_pitch) > params.manual_threshold)
- {
- speed_body_x = -manual_pitch * params.limit_speed_x * speed_limit_height_factor;
- update_flow_sp_sumx = true;
- }
-
- if(fabsf(manual_roll) > params.manual_threshold)
- {
- speed_body_y = manual_roll * params.limit_speed_y * speed_limit_height_factor;
- update_flow_sp_sumy = true;
- }
- }
-
- /* limit speed setpoints */
- if((speed_body_x <= params.limit_speed_x * speed_limit_height_factor) &&
- (speed_body_x >= -params.limit_speed_x * speed_limit_height_factor))
- {
- speed_sp.vx = speed_body_x;
- }
- else
- {
- if(speed_body_x > params.limit_speed_x * speed_limit_height_factor)
- speed_sp.vx = params.limit_speed_x * speed_limit_height_factor;
- if(speed_body_x < -params.limit_speed_x * speed_limit_height_factor)
- speed_sp.vx = -params.limit_speed_x * speed_limit_height_factor;
- }
-
- if((speed_body_y <= params.limit_speed_y * speed_limit_height_factor) &&
- (speed_body_y >= -params.limit_speed_y * speed_limit_height_factor))
- {
- speed_sp.vy = speed_body_y;
- }
- else
- {
- if(speed_body_y > params.limit_speed_y * speed_limit_height_factor)
- speed_sp.vy = params.limit_speed_y * speed_limit_height_factor;
- if(speed_body_y < -params.limit_speed_y * speed_limit_height_factor)
- speed_sp.vy = -params.limit_speed_y * speed_limit_height_factor;
- }
-
- /* manual yaw change */
- if(isfinite(manual_yaw) && isfinite(manual.throttle))
- {
- if(fabsf(manual_yaw) > params.manual_threshold && manual.throttle > 0.2f)
- {
- yaw_sp += manual_yaw * params.limit_yaw_step;
-
- /* modulo for rotation -pi +pi */
- if(yaw_sp < -M_PI_F)
- yaw_sp = yaw_sp + M_TWOPI_F;
- else if(yaw_sp > M_PI_F)
- yaw_sp = yaw_sp - M_TWOPI_F;
- }
- }
-
- /* forward yaw setpoint */
- speed_sp.yaw_sp = yaw_sp;
-
-
- /* manual height control
- * 0-20%: thrust linear down
- * 20%-40%: down
- * 40%-60%: stabilize altitude
- * 60-100%: up
- */
- float thrust_control = 0.0f;
-
- if (isfinite(manual.throttle))
- {
- if (start_phase)
- {
- /* control start thrust with stick input */
- if (manual.throttle < 0.4f)
- {
- /* first 40% for up to feedforward */
- thrust_control = manual.throttle / 0.4f * params.thrust_feedforward;
- }
- else
- {
- /* second 60% for up to feedforward + 10% */
- thrust_control = (manual.throttle - 0.4f) / 0.6f * 0.1f + params.thrust_feedforward;
- }
-
- /* exit start phase if setpoint is reached */
- if (height_sp < -local_pos.z && thrust_control > params.limit_thrust_lower)
- {
- start_phase = false;
- /* switch to stabilize */
- thrust_control = params.thrust_feedforward;
- }
- }
- else
- {
- if (manual.throttle < 0.2f)
- {
- /* landing initialization */
- if (!landing_initialized)
- {
- /* consider last thrust control to avoid steps */
- landing_thrust_start = speed_sp.thrust_sp;
- landing_initialized = true;
- }
-
- /* set current height as setpoint to avoid steps */
- if (-local_pos.z > params.height_min)
- height_sp = -local_pos.z;
- else
- height_sp = params.height_min;
-
- /* lower 20% stick range controls thrust down */
- thrust_control = manual.throttle / 0.2f * landing_thrust_start;
-
- /* assume ground position here */
- if (thrust_control < 0.1f)
- {
- /* reset integral if on ground */
- integrated_h_error = 0.0f;
- /* switch to start phase */
- start_phase = true;
- /* reset height setpoint */
- height_sp = params.height_min;
- }
- }
- else
- {
- /* stabilized mode */
- landing_initialized = false;
-
- /* calc new thrust with PID */
- float height_error = (local_pos.z - (-height_sp));
-
- /* update height setpoint if needed*/
- if (manual.throttle < 0.4f)
- {
- /* down */
- if (height_sp > params.height_min + params.height_rate &&
- fabsf(height_error) < params.limit_height_error)
- height_sp -= params.height_rate * dt;
- }
-
- if (manual.throttle > 0.6f)
- {
- /* up */
- if (height_sp < params.height_max &&
- fabsf(height_error) < params.limit_height_error)
- height_sp += params.height_rate * dt;
- }
-
- /* instead of speed limitation, limit height error (downwards) */
- if(height_error > params.limit_height_error)
- height_error = params.limit_height_error;
- else if(height_error < -params.limit_height_error)
- height_error = -params.limit_height_error;
-
- integrated_h_error = integrated_h_error + height_error;
- float integrated_thrust_addition = integrated_h_error * params.height_i;
-
- if(integrated_thrust_addition > params.limit_thrust_int)
- integrated_thrust_addition = params.limit_thrust_int;
- if(integrated_thrust_addition < -params.limit_thrust_int)
- integrated_thrust_addition = -params.limit_thrust_int;
-
- float height_speed = last_local_pos_z - local_pos.z;
- float thrust_diff = height_error * params.height_p - height_speed * params.height_d;
-
- thrust_control = params.thrust_feedforward + thrust_diff + integrated_thrust_addition;
-
- /* add attitude component
- * F = Fz / (cos(pitch)*cos(roll)) -> can be found in rotM
- */
-// // TODO problem with attitude
-// if (att.R_valid && att.R[2][2] > 0)
-// thrust_control = thrust_control / att.R[2][2];
-
- /* set thrust lower limit */
- if(thrust_control < params.limit_thrust_lower)
- thrust_control = params.limit_thrust_lower;
- }
- }
-
- /* set thrust upper limit */
- if(thrust_control > params.limit_thrust_upper)
- thrust_control = params.limit_thrust_upper;
- }
- /* store actual height for speed estimation */
- last_local_pos_z = local_pos.z;
-
- speed_sp.thrust_sp = thrust_control; //manual.throttle;
- speed_sp.timestamp = hrt_absolute_time();
-
- /* publish new speed setpoint */
- if(isfinite(speed_sp.vx) && isfinite(speed_sp.vy) && isfinite(speed_sp.yaw_sp) && isfinite(speed_sp.thrust_sp))
- {
-
- if(speed_setpoint_adverted)
- {
- orb_publish(ORB_ID(vehicle_bodyframe_speed_setpoint), speed_sp_pub, &speed_sp);
- }
- else
- {
- speed_sp_pub = orb_advertise(ORB_ID(vehicle_bodyframe_speed_setpoint), &speed_sp);
- speed_setpoint_adverted = true;
- }
- }
- else
- {
- warnx("NaN in flow position controller!");
- }
- }
- else
- {
- /* in manual or stabilized state just reset speed and flow sum setpoint */
- //mavlink_log_info(mavlink_fd,"[fpc] reset speed sp, flow_sp_sumx,y (%f,%f)",filtered_flow.sumx, filtered_flow.sumy);
- if(status_changed == true)
- mavlink_log_info(mavlink_fd,"[fpc] flow POSITION controller disengaged.");
-
- status_changed = false;
- speed_sp.vx = 0.0f;
- speed_sp.vy = 0.0f;
- flow_sp_sumx = filtered_flow.sumx;
- flow_sp_sumy = filtered_flow.sumy;
- if(isfinite(att.yaw))
- {
- yaw_sp = att.yaw;
- speed_sp.yaw_sp = att.yaw;
- }
- if(isfinite(manual.throttle))
- speed_sp.thrust_sp = manual.throttle;
- }
- /* measure in what intervals the controller runs */
- perf_count(mc_interval_perf);
- perf_end(mc_loop_perf);
- }
- }
-
- counter++;
- }
- else
- {
- /* sensors not ready waiting for first attitude msg */
-
- /* polling */
- struct pollfd fds[1] = {
- { .fd = vehicle_attitude_sub, .events = POLLIN },
- };
-
- /* wait for a flow msg, check for exit condition every 5 s */
- int ret = poll(fds, 1, 5000);
-
- if (ret < 0)
- {
- /* poll error, count it in perf */
- perf_count(mc_err_perf);
- }
- else if (ret == 0)
- {
- /* no return value, ignore */
- mavlink_log_info(mavlink_fd,"[fpc] no attitude received.\n");
- }
- else
- {
- if (fds[0].revents & POLLIN)
- {
- sensors_ready = true;
- mavlink_log_info(mavlink_fd,"[fpc] initialized.\n");
- }
- }
- }
- }
-
- mavlink_log_info(mavlink_fd,"[fpc] ending now...\n");
-
- thread_running = false;
-
- close(parameter_update_sub);
- close(vehicle_attitude_sub);
- close(vehicle_local_position_sub);
- close(armed_sub);
- close(control_mode_sub);
- close(manual_control_setpoint_sub);
- close(speed_sp_pub);
-
- perf_print_counter(mc_loop_perf);
- perf_free(mc_loop_perf);
-
- fflush(stdout);
- return 0;
-}
-
diff --git a/src/examples/flow_position_control/flow_position_control_params.c b/src/examples/flow_position_control/flow_position_control_params.c
deleted file mode 100644
index eb1473647..000000000
--- a/src/examples/flow_position_control/flow_position_control_params.c
+++ /dev/null
@@ -1,124 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * @file flow_position_control_params.c
- */
-
-#include "flow_position_control_params.h"
-
-/* controller parameters */
-
-// Position control P gain
-PARAM_DEFINE_FLOAT(FPC_POS_P, 3.0f);
-// Position control D / damping gain
-PARAM_DEFINE_FLOAT(FPC_POS_D, 0.0f);
-// Altitude control P gain
-PARAM_DEFINE_FLOAT(FPC_H_P, 0.15f);
-// Altitude control I (integrator) gain
-PARAM_DEFINE_FLOAT(FPC_H_I, 0.00001f);
-// Altitude control D gain
-PARAM_DEFINE_FLOAT(FPC_H_D, 0.8f);
-// Altitude control rate limiter
-PARAM_DEFINE_FLOAT(FPC_H_RATE, 0.1f);
-// Altitude control minimum altitude
-PARAM_DEFINE_FLOAT(FPC_H_MIN, 0.5f);
-// Altitude control maximum altitude (higher than 1.5m is untested)
-PARAM_DEFINE_FLOAT(FPC_H_MAX, 1.5f);
-// Altitude control feed forward throttle - adjust to the
-// throttle position (0..1) where the copter hovers in manual flight
-PARAM_DEFINE_FLOAT(FPC_T_FFWD, 0.7f); // adjust this before flight
-PARAM_DEFINE_FLOAT(FPC_L_S_X, 1.2f);
-PARAM_DEFINE_FLOAT(FPC_L_S_Y, 1.2f);
-PARAM_DEFINE_FLOAT(FPC_L_H_ERR, 0.1f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_I, 0.05f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_U, 0.8f);
-PARAM_DEFINE_FLOAT(FPC_L_TH_L, 0.6f);
-PARAM_DEFINE_FLOAT(FPC_L_YAW_STEP, 0.03f);
-PARAM_DEFINE_FLOAT(FPC_MAN_THR, 0.1f);
-
-
-int parameters_init(struct flow_position_control_param_handles *h)
-{
- /* PID parameters */
- h->pos_p = param_find("FPC_POS_P");
- h->pos_d = param_find("FPC_POS_D");
- h->height_p = param_find("FPC_H_P");
- h->height_i = param_find("FPC_H_I");
- h->height_d = param_find("FPC_H_D");
- h->height_rate = param_find("FPC_H_RATE");
- h->height_min = param_find("FPC_H_MIN");
- h->height_max = param_find("FPC_H_MAX");
- h->thrust_feedforward = param_find("FPC_T_FFWD");
- h->limit_speed_x = param_find("FPC_L_S_X");
- h->limit_speed_y = param_find("FPC_L_S_Y");
- h->limit_height_error = param_find("FPC_L_H_ERR");
- h->limit_thrust_int = param_find("FPC_L_TH_I");
- h->limit_thrust_upper = param_find("FPC_L_TH_U");
- h->limit_thrust_lower = param_find("FPC_L_TH_L");
- h->limit_yaw_step = param_find("FPC_L_YAW_STEP");
- h->manual_threshold = param_find("FPC_MAN_THR");
- h->rc_scale_pitch = param_find("RC_SCALE_PITCH");
- h->rc_scale_roll = param_find("RC_SCALE_ROLL");
- h->rc_scale_yaw = param_find("RC_SCALE_YAW");
-
- return OK;
-}
-
-int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p)
-{
- param_get(h->pos_p, &(p->pos_p));
- param_get(h->pos_d, &(p->pos_d));
- param_get(h->height_p, &(p->height_p));
- param_get(h->height_i, &(p->height_i));
- param_get(h->height_d, &(p->height_d));
- param_get(h->height_rate, &(p->height_rate));
- param_get(h->height_min, &(p->height_min));
- param_get(h->height_max, &(p->height_max));
- param_get(h->thrust_feedforward, &(p->thrust_feedforward));
- param_get(h->limit_speed_x, &(p->limit_speed_x));
- param_get(h->limit_speed_y, &(p->limit_speed_y));
- param_get(h->limit_height_error, &(p->limit_height_error));
- param_get(h->limit_thrust_int, &(p->limit_thrust_int));
- param_get(h->limit_thrust_upper, &(p->limit_thrust_upper));
- param_get(h->limit_thrust_lower, &(p->limit_thrust_lower));
- param_get(h->limit_yaw_step, &(p->limit_yaw_step));
- param_get(h->manual_threshold, &(p->manual_threshold));
- param_get(h->rc_scale_pitch, &(p->rc_scale_pitch));
- param_get(h->rc_scale_roll, &(p->rc_scale_roll));
- param_get(h->rc_scale_yaw, &(p->rc_scale_yaw));
-
- return OK;
-}
diff --git a/src/examples/flow_position_control/flow_position_control_params.h b/src/examples/flow_position_control/flow_position_control_params.h
deleted file mode 100644
index d0c8fc722..000000000
--- a/src/examples/flow_position_control/flow_position_control_params.h
+++ /dev/null
@@ -1,100 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
- * Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * @file flow_position_control_params.h
- *
- * Parameters for position controller
- */
-
-#include <systemlib/param/param.h>
-
-struct flow_position_control_params {
- float pos_p;
- float pos_d;
- float height_p;
- float height_i;
- float height_d;
- float height_rate;
- float height_min;
- float height_max;
- float thrust_feedforward;
- float limit_speed_x;
- float limit_speed_y;
- float limit_height_error;
- float limit_thrust_int;
- float limit_thrust_upper;
- float limit_thrust_lower;
- float limit_yaw_step;
- float manual_threshold;
- float rc_scale_pitch;
- float rc_scale_roll;
- float rc_scale_yaw;
-};
-
-struct flow_position_control_param_handles {
- param_t pos_p;
- param_t pos_d;
- param_t height_p;
- param_t height_i;
- param_t height_d;
- param_t height_rate;
- param_t height_min;
- param_t height_max;
- param_t thrust_feedforward;
- param_t limit_speed_x;
- param_t limit_speed_y;
- param_t limit_height_error;
- param_t limit_thrust_int;
- param_t limit_thrust_upper;
- param_t limit_thrust_lower;
- param_t limit_yaw_step;
- param_t manual_threshold;
- param_t rc_scale_pitch;
- param_t rc_scale_roll;
- param_t rc_scale_yaw;
-};
-
-/**
- * Initialize all parameter handles and values
- *
- */
-int parameters_init(struct flow_position_control_param_handles *h);
-
-/**
- * Update all parameters
- *
- */
-int parameters_update(const struct flow_position_control_param_handles *h, struct flow_position_control_params *p);
diff --git a/src/examples/flow_position_control/module.mk b/src/examples/flow_position_control/module.mk
deleted file mode 100644
index b10dc490a..000000000
--- a/src/examples/flow_position_control/module.mk
+++ /dev/null
@@ -1,41 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Build multirotor position control
-#
-
-MODULE_COMMAND = flow_position_control
-
-SRCS = flow_position_control_main.c \
- flow_position_control_params.c
diff --git a/src/examples/flow_position_estimator/flow_position_estimator_main.c b/src/examples/flow_position_estimator/flow_position_estimator_main.c
index 495c415f2..c775428ef 100644
--- a/src/examples/flow_position_estimator/flow_position_estimator_main.c
+++ b/src/examples/flow_position_estimator/flow_position_estimator_main.c
@@ -65,6 +65,7 @@
#include <uORB/topics/optical_flow.h>
#include <uORB/topics/filtered_bottom_flow.h>
#include <systemlib/perf_counter.h>
+#include <systemlib/systemlib.h>
#include <poll.h>
#include "flow_position_estimator_params.h"
@@ -109,9 +110,9 @@ int flow_position_estimator_main(int argc, char *argv[])
thread_should_exit = false;
daemon_task = task_spawn_cmd("flow_position_estimator",
- SCHED_RR,
+ SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4096,
+ 4000,
flow_position_estimator_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_daemon_app/module.mk b/src/examples/px4_daemon_app/module.mk
index 5f8aa73d5..fc4223142 100644
--- a/src/examples/px4_daemon_app/module.mk
+++ b/src/examples/px4_daemon_app/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/examples/px4_daemon_app/px4_daemon_app.c b/src/examples/px4_daemon_app/px4_daemon_app.c
index 53f1b4a9a..3eaf14148 100644
--- a/src/examples/px4_daemon_app/px4_daemon_app.c
+++ b/src/examples/px4_daemon_app/px4_daemon_app.c
@@ -98,7 +98,7 @@ int px4_daemon_app_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("daemon",
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 4096,
+ 2000,
px4_daemon_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
exit(0);
diff --git a/src/examples/px4_mavlink_debug/module.mk b/src/examples/px4_mavlink_debug/module.mk
index fefd61496..c7ef97fc4 100644
--- a/src/examples/px4_mavlink_debug/module.mk
+++ b/src/examples/px4_mavlink_debug/module.mk
@@ -37,4 +37,6 @@
MODULE_COMMAND = px4_mavlink_debug
-SRCS = px4_mavlink_debug.c \ No newline at end of file
+SRCS = px4_mavlink_debug.c
+
+MODULE_STACKSIZE = 2000
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 9584924cc..0a909d02f 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -63,11 +63,22 @@ ECL_PitchController::ECL_PitchController() :
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f)
{
+ perf_alloc(PC_COUNT, "fw att control pitch nonfinite input");
}
-float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
+ECL_PitchController::~ECL_PitchController()
{
+ perf_free(_nonfinite_input_perf);
+}
+float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
+{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(pitch_setpoint) && isfinite(roll) && isfinite(pitch) && isfinite(airspeed))) {
+ perf_count(_nonfinite_input_perf);
+ warnx("not controlling pitch");
+ return _rate_setpoint;
+ }
/* flying inverted (wings upside down) ? */
bool inverted = false;
@@ -123,6 +134,14 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
float yaw_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
+ isfinite(yaw_rate_setpoint) && isfinite(airspeed_min) &&
+ isfinite(airspeed_max) && isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
+
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
index 30a82a86a..39b9f9d03 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -51,12 +51,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_PitchController //XXX: create controller superclass
{
public:
ECL_PitchController();
+ ~ECL_PitchController();
+
float control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed);
@@ -126,6 +129,7 @@ private:
float _rate_error;
float _rate_setpoint;
float _bodyrate_setpoint;
+ perf_counter_t _nonfinite_input_perf;
};
#endif // ECL_PITCH_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 2e86c72dc..82903ef5a 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -61,10 +61,21 @@ ECL_RollController::ECL_RollController() :
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f)
{
+ perf_alloc(PC_COUNT, "fw att control roll nonfinite input");
+}
+
+ECL_RollController::~ECL_RollController()
+{
+ perf_free(_nonfinite_input_perf);
}
float ECL_RollController::control_attitude(float roll_setpoint, float roll)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll_setpoint) && isfinite(roll))) {
+ perf_count(_nonfinite_input_perf);
+ return _rate_setpoint;
+ }
/* Calculate error */
float roll_error = roll_setpoint - roll;
@@ -86,6 +97,14 @@ float ECL_RollController::control_bodyrate(float pitch,
float yaw_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(pitch) && isfinite(roll_rate) && isfinite(yaw_rate) && isfinite(yaw_rate_setpoint) &&
+ isfinite(airspeed_min) && isfinite(airspeed_max) &&
+ isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
+
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
@@ -122,8 +141,8 @@ float ECL_RollController::control_bodyrate(float pitch,
float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase if actuator is at limit
- */
+ * anti-windup: do not allow integrator to increase if actuator is at limit
+ */
if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
index 92c64b95f..0799dbe03 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -51,12 +51,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_RollController //XXX: create controller superclass
{
public:
ECL_RollController();
+ ~ECL_RollController();
+
float control_attitude(float roll_setpoint, float roll);
float control_bodyrate(float pitch,
@@ -117,6 +120,7 @@ private:
float _rate_error;
float _rate_setpoint;
float _bodyrate_setpoint;
+ perf_counter_t _nonfinite_input_perf;
};
#endif // ECL_ROLL_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
index 255776765..e53ffc644 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -60,12 +60,25 @@ ECL_YawController::ECL_YawController() :
_bodyrate_setpoint(0.0f),
_coordinated_min_speed(1.0f)
{
+ perf_alloc(PC_COUNT, "fw att control yaw nonfinite input");
+}
+
+ECL_YawController::~ECL_YawController()
+{
+ perf_free(_nonfinite_input_perf);
}
float ECL_YawController::control_attitude(float roll, float pitch,
float speed_body_u, float speed_body_v, float speed_body_w,
float roll_rate_setpoint, float pitch_rate_setpoint)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(speed_body_u) && isfinite(speed_body_v) &&
+ isfinite(speed_body_w) && isfinite(roll_rate_setpoint) &&
+ isfinite(pitch_rate_setpoint))) {
+ perf_count(_nonfinite_input_perf);
+ return _rate_setpoint;
+ }
// static int counter = 0;
/* Calculate desired yaw rate from coordinated turn constraint / (no side forces) */
_rate_setpoint = 0.0f;
@@ -103,6 +116,13 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
float pitch_rate_setpoint,
float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
+ isfinite(pitch_rate_setpoint) && isfinite(airspeed_min) &&
+ isfinite(airspeed_max) && isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
index 03f3202d0..a360c14b8 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -50,12 +50,15 @@
#include <stdbool.h>
#include <stdint.h>
+#include <systemlib/perf_counter.h>
class __EXPORT ECL_YawController //XXX: create controller superclass
{
public:
ECL_YawController();
+ ~ECL_YawController();
+
float control_attitude(float roll, float pitch,
float speed_body_u, float speed_body_v, float speed_body_w,
float roll_rate_setpoint, float pitch_rate_setpoint);
@@ -118,6 +121,7 @@ private:
float _rate_setpoint;
float _bodyrate_setpoint;
float _coordinated_min_speed;
+ perf_counter_t _nonfinite_input_perf;
};
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
index 0a3f85d97..e2f3da6f8 100644
--- a/src/lib/geo/geo.h
+++ b/src/lib/geo/geo.h
@@ -50,6 +50,8 @@
__BEGIN_DECLS
+#include "geo/geo_mag_declination.h"
+
#include <stdbool.h>
#define CONSTANTS_ONE_G 9.80665f /* m/s^2 */
diff --git a/src/lib/geo/geo_mag_declination.c b/src/lib/geo/geo_mag_declination.c
new file mode 100644
index 000000000..09eac38f4
--- /dev/null
+++ b/src/lib/geo/geo_mag_declination.c
@@ -0,0 +1,136 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 MAV GEO Library (MAVGEO). 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 MAVGEO 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 geo_mag_declination.c
+*
+* Calculation / lookup table for earth magnetic field declination.
+*
+* Lookup table from Scott Ferguson <scottfromscott@gmail.com>
+*
+* XXX Lookup table currently too coarse in resolution (only full degrees)
+* and lat/lon res - needs extension medium term.
+*
+*/
+
+#include <geo/geo.h>
+
+/** set this always to the sampling in degrees for the table below */
+#define SAMPLING_RES 10.0f
+#define SAMPLING_MIN_LAT -60.0f
+#define SAMPLING_MAX_LAT 60.0f
+#define SAMPLING_MIN_LON -180.0f
+#define SAMPLING_MAX_LON 180.0f
+
+static const int8_t declination_table[13][37] = \
+{
+ 46, 45, 44, 42, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -40, -48, -55, -61, \
+ -66, -71, -74, -75, -72, -61, -25, 22, 40, 45, 47, 46, 30, 30, 30, 30, 29, 29, 29, 29, 27, 24, 18, 11, 3, \
+ -3, -9, -12, -15, -17, -21, -26, -32, -39, -45, -51, -55, -57, -56, -53, -44, -31, -14, 0, 13, 21, 26, \
+ 29, 30, 21, 22, 22, 22, 22, 22, 22, 22, 21, 18, 13, 5, -3, -11, -17, -20, -21, -22, -23, -25, -29, -35, \
+ -40, -44, -45, -44, -40, -32, -22, -12, -3, 3, 9, 14, 18, 20, 21, 16, 17, 17, 17, 17, 17, 16, 16, 16, 13, \
+ 8, 0, -9, -16, -21, -24, -25, -25, -23, -20, -21, -24, -28, -31, -31, -29, -24, -17, -9, -3, 0, 4, 7, \
+ 10, 13, 15, 16, 12, 13, 13, 13, 13, 13, 12, 12, 11, 9, 3, -4, -12, -19, -23, -24, -24, -22, -17, -12, -9, \
+ -10, -13, -17, -18, -16, -13, -8, -3, 0, 1, 3, 6, 8, 10, 12, 12, 10, 10, 10, 10, 10, 10, 10, 9, 9, 6, 0, -6, \
+ -14, -20, -22, -22, -19, -15, -10, -6, -2, -2, -4, -7, -8, -8, -7, -4, 0, 1, 1, 2, 4, 6, 8, 10, 10, 9, 9, 9, \
+ 9, 9, 9, 8, 8, 7, 4, -1, -8, -15, -19, -20, -18, -14, -9, -5, -2, 0, 1, 0, -2, -3, -4, -3, -2, 0, 0, 0, 1, 3, 5, \
+ 7, 8, 9, 8, 8, 8, 9, 9, 9, 8, 8, 6, 2, -3, -9, -15, -18, -17, -14, -10, -6, -2, 0, 1, 2, 2, 0, -1, -1, -2, -1, 0, \
+ 0, 0, 0, 1, 3, 5, 7, 8, 8, 9, 9, 10, 10, 10, 10, 8, 5, 0, -5, -11, -15, -16, -15, -12, -8, -4, -1, 0, 2, 3, 2, 1, 0, \
+ 0, 0, 0, 0, -1, -2, -2, -1, 0, 3, 6, 8, 6, 9, 10, 11, 12, 12, 11, 9, 5, 0, -7, -12, -15, -15, -13, -10, -7, -3, \
+ 0, 1, 2, 3, 3, 3, 2, 1, 0, 0, -1, -3, -4, -5, -5, -2, 0, 3, 6, 5, 8, 11, 13, 15, 15, 14, 11, 5, -1, -9, -14, -17, \
+ -16, -14, -11, -7, -3, 0, 1, 3, 4, 5, 5, 5, 4, 3, 1, -1, -4, -7, -8, -8, -6, -2, 1, 5, 4, 8, 12, 15, 17, 18, 16, \
+ 12, 5, -3, -12, -18, -20, -19, -16, -13, -8, -4, -1, 1, 4, 6, 8, 9, 9, 9, 7, 3, -1, -6, -10, -12, -11, -9, -5, \
+ 0, 4, 3, 9, 14, 17, 20, 21, 19, 14, 4, -8, -19, -25, -26, -25, -21, -17, -12, -7, -2, 1, 5, 9, 13, 15, 16, 16, \
+ 13, 7, 0, -7, -12, -15, -14, -11, -6, -1, 3
+};
+
+static float get_lookup_table_val(unsigned lat, unsigned lon);
+
+__EXPORT float get_mag_declination(float lat, float lon)
+{
+ /*
+ * If the values exceed valid ranges, return zero as default
+ * as we have no way of knowing what the closest real value
+ * would be.
+ */
+ if (lat < -90.0f || lat > 90.0f ||
+ lon < -180.0f || lon > 180.0f) {
+ return 0.0f;
+ }
+
+ /* round down to nearest sampling resolution */
+ int min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES;
+ int min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES;
+
+ /* for the rare case of hitting the bounds exactly
+ * the rounding logic wouldn't fit, so enforce it.
+ */
+
+ /* limit to table bounds - required for maxima even when table spans full globe range */
+ if (lat <= SAMPLING_MIN_LAT) {
+ min_lat = SAMPLING_MIN_LAT;
+ }
+
+ if (lat >= SAMPLING_MAX_LAT) {
+ min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
+ }
+
+ if (lon <= SAMPLING_MIN_LON) {
+ min_lon = SAMPLING_MIN_LON;
+ }
+
+ if (lon >= SAMPLING_MAX_LON) {
+ min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
+ }
+
+ /* find index of nearest low sampling point */
+ unsigned min_lat_index = (-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES;
+ unsigned min_lon_index = (-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES;
+
+ float declination_sw = get_lookup_table_val(min_lat_index, min_lon_index);
+ float declination_se = get_lookup_table_val(min_lat_index, min_lon_index + 1);
+ float declination_ne = get_lookup_table_val(min_lat_index + 1, min_lon_index + 1);
+ float declination_nw = get_lookup_table_val(min_lat_index + 1, min_lon_index);
+
+ /* perform bilinear interpolation on the four grid corners */
+
+ float declination_min = ((lon - min_lon) / SAMPLING_RES) * (declination_se - declination_sw) + declination_sw;
+ float declination_max = ((lon - min_lon) / SAMPLING_RES) * (declination_ne - declination_nw) + declination_nw;
+
+ return ((lat - min_lat) / SAMPLING_RES) * (declination_max - declination_min) + declination_min;
+}
+
+float get_lookup_table_val(unsigned lat_index, unsigned lon_index)
+{
+ return declination_table[lat_index][lon_index];
+} \ No newline at end of file
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h b/src/lib/geo/geo_mag_declination.h
index 500e3e197..0ac062d6d 100644
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.h
+++ b/src/lib/geo/geo_mag_declination.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- *
+ * Copyright (c) 2014 MAV GEO Library (MAVGEO). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -14,7 +12,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
+ * 3. Neither the name MAVGEO nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -33,16 +31,17 @@
*
****************************************************************************/
-/* @file Fixed Wing Attitude Rate Control */
+/**
+* @file geo_mag_declination.h
+*
+* Calculation / lookup table for earth magnetic field declination.
+*
+*/
-#ifndef FIXEDWING_ATT_CONTROL_RATE_H_
-#define FIXEDWING_ATT_CONTROL_RATE_H_
+#pragma once
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/actuator_controls.h>
+__BEGIN_DECLS
-int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[],
- struct actuator_controls_s *actuators);
+__EXPORT float get_mag_declination(float lat, float lon);
-#endif /* FIXEDWING_ATT_CONTROL_RATE_H_ */
+__END_DECLS
diff --git a/src/lib/geo/module.mk b/src/lib/geo/module.mk
index 30a2dc99f..9500a2bcc 100644
--- a/src/lib/geo/module.mk
+++ b/src/lib/geo/module.mk
@@ -35,4 +35,5 @@
# Geo library
#
-SRCS = geo.c
+SRCS = geo.c \
+ geo_mag_declination.c
diff --git a/src/lib/mathlib/CMSIS/Include/arm_math.h b/src/lib/mathlib/CMSIS/Include/arm_math.h
index 6f66f9ee3..61d3a3b61 100644
--- a/src/lib/mathlib/CMSIS/Include/arm_math.h
+++ b/src/lib/mathlib/CMSIS/Include/arm_math.h
@@ -5193,7 +5193,7 @@ void arm_rfft_fast_f32(
*pIa = Ialpha;
/* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */
- *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
+ *pIb = (float32_t)-0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
}
diff --git a/src/lib/version/version.h b/src/lib/version/version.h
index af733aaf0..d8ccb6774 100644
--- a/src/lib/version/version.h
+++ b/src/lib/version/version.h
@@ -59,4 +59,8 @@
#define HW_ARCH "PX4FMU_V2"
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+#define HW_ARCH "AEROCORE"
+#endif
+
#endif /* VERSION_H_ */
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp b/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
deleted file mode 100644
index 5cf84542b..000000000
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.cpp
+++ /dev/null
@@ -1,812 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file KalmanNav.cpp
- *
- * Kalman filter navigation code
- */
-
-#include <poll.h>
-
-#include "KalmanNav.hpp"
-#include <systemlib/err.h>
-#include <geo/geo.h>
-
-// constants
-// Titterton pg. 52
-static const float omega = 7.2921150e-5f; // earth rotation rate, rad/s
-static const float R0 = 6378137.0f; // earth radius, m
-static const float g0 = 9.806f; // standard gravitational accel. m/s^2
-static const int8_t ret_ok = 0; // no error in function
-static const int8_t ret_error = -1; // error occurred
-
-KalmanNav::KalmanNav(SuperBlock *parent, const char *name) :
- SuperBlock(parent, name),
- // subscriptions
- _sensors(&getSubscriptions(), ORB_ID(sensor_combined), 5), // limit to 200 Hz
- _gps(&getSubscriptions(), ORB_ID(vehicle_gps_position), 100), // limit to 10 Hz
- _param_update(&getSubscriptions(), ORB_ID(parameter_update), 1000), // limit to 1 Hz
- // publications
- _pos(&getPublications(), ORB_ID(vehicle_global_position)),
- _localPos(&getPublications(), ORB_ID(vehicle_local_position)),
- _att(&getPublications(), ORB_ID(vehicle_attitude)),
- // timestamps
- _pubTimeStamp(hrt_absolute_time()),
- _predictTimeStamp(hrt_absolute_time()),
- _attTimeStamp(hrt_absolute_time()),
- _outTimeStamp(hrt_absolute_time()),
- // frame count
- _navFrames(0),
- // miss counts
- _miss(0),
- // accelerations
- fN(0), fE(0), fD(0),
- // state
- phi(0), theta(0), psi(0),
- vN(0), vE(0), vD(0),
- lat(0), lon(0), alt(0),
- lat0(0), lon0(0), alt0(0),
- // parameters for ground station
- _vGyro(this, "V_GYRO"),
- _vAccel(this, "V_ACCEL"),
- _rMag(this, "R_MAG"),
- _rGpsVel(this, "R_GPS_VEL"),
- _rGpsPos(this, "R_GPS_POS"),
- _rGpsAlt(this, "R_GPS_ALT"),
- _rPressAlt(this, "R_PRESS_ALT"),
- _rAccel(this, "R_ACCEL"),
- _magDip(this, "ENV_MAG_DIP"),
- _magDec(this, "ENV_MAG_DEC"),
- _g(this, "ENV_G"),
- _faultPos(this, "FAULT_POS"),
- _faultAtt(this, "FAULT_ATT"),
- _attitudeInitialized(false),
- _positionInitialized(false),
- _attitudeInitCounter(0)
-{
- using namespace math;
-
- memset(&ref, 0, sizeof(ref));
-
- F.zero();
- G.zero();
- V.zero();
- HAtt.zero();
- RAtt.zero();
- HPos.zero();
- RPos.zero();
-
- // initial state covariance matrix
- P0.identity();
- P0 *= 0.01f;
- P = P0;
-
- // initial state
- phi = 0.0f;
- theta = 0.0f;
- psi = 0.0f;
- vN = 0.0f;
- vE = 0.0f;
- vD = 0.0f;
- lat = 0.0f;
- lon = 0.0f;
- alt = 0.0f;
-
- // initialize rotation quaternion with a single raw sensor measurement
- _sensors.update();
- q = init(
- _sensors.accelerometer_m_s2[0],
- _sensors.accelerometer_m_s2[1],
- _sensors.accelerometer_m_s2[2],
- _sensors.magnetometer_ga[0],
- _sensors.magnetometer_ga[1],
- _sensors.magnetometer_ga[2]);
-
- // initialize dcm
- C_nb = q.to_dcm();
-
- // HPos is constant
- HPos(0, 3) = 1.0f;
- HPos(1, 4) = 1.0f;
- HPos(2, 6) = 1.0e7f * M_RAD_TO_DEG_F;
- HPos(3, 7) = 1.0e7f * M_RAD_TO_DEG_F;
- HPos(4, 8) = 1.0f;
- HPos(5, 8) = 1.0f;
-
- // initialize all parameters
- updateParams();
-}
-
-math::Quaternion KalmanNav::init(float ax, float ay, float az, float mx, float my, float mz)
-{
- float initialRoll, initialPitch;
- float cosRoll, sinRoll, cosPitch, sinPitch;
- float magX, magY;
- float initialHdg, cosHeading, sinHeading;
-
- initialRoll = atan2(-ay, -az);
- initialPitch = atan2(ax, -az);
-
- cosRoll = cosf(initialRoll);
- sinRoll = sinf(initialRoll);
- cosPitch = cosf(initialPitch);
- sinPitch = sinf(initialPitch);
-
- magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
-
- magY = my * cosRoll - mz * sinRoll;
-
- initialHdg = atan2f(-magY, magX);
-
- cosRoll = cosf(initialRoll * 0.5f);
- sinRoll = sinf(initialRoll * 0.5f);
-
- cosPitch = cosf(initialPitch * 0.5f);
- sinPitch = sinf(initialPitch * 0.5f);
-
- cosHeading = cosf(initialHdg * 0.5f);
- sinHeading = sinf(initialHdg * 0.5f);
-
- float q0 = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
- float q1 = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
- float q2 = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
- float q3 = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
-
- return math::Quaternion(q0, q1, q2, q3);
-
-}
-
-void KalmanNav::update()
-{
- using namespace math;
-
- struct pollfd fds[1];
- fds[0].fd = _sensors.getHandle();
- fds[0].events = POLLIN;
-
- // poll for new data
- int ret = poll(fds, 1, 1000);
-
- if (ret < 0) {
- // XXX this is seriously bad - should be an emergency
- return;
-
- } else if (ret == 0) { // timeout
- return;
- }
-
- // get new timestamp
- uint64_t newTimeStamp = hrt_absolute_time();
-
- // check updated subscriptions
- if (_param_update.updated()) updateParams();
-
- bool gpsUpdate = _gps.updated();
- bool sensorsUpdate = _sensors.updated();
-
- // get new information from subscriptions
- // this clears update flag
- updateSubscriptions();
-
- // initialize attitude when sensors online
- if (!_attitudeInitialized && sensorsUpdate) {
- if (correctAtt() == ret_ok) _attitudeInitCounter++;
-
- if (_attitudeInitCounter > 100) {
- warnx("initialized EKF attitude");
- warnx("phi: %8.4f, theta: %8.4f, psi: %8.4f",
- double(phi), double(theta), double(psi));
- _attitudeInitialized = true;
- }
- }
-
- // initialize position when gps received
- if (!_positionInitialized &&
- _attitudeInitialized && // wait for attitude first
- gpsUpdate &&
- _gps.fix_type > 2
- //&& _gps.counter_pos_valid > 10
- ) {
- vN = _gps.vel_n_m_s;
- vE = _gps.vel_e_m_s;
- vD = _gps.vel_d_m_s;
- setLatDegE7(_gps.lat);
- setLonDegE7(_gps.lon);
- setAltE3(_gps.alt);
- // set reference position for
- // local position
- lat0 = lat;
- lon0 = lon;
- alt0 = alt;
- map_projection_init(&ref, lat0, lon0);
- _positionInitialized = true;
- warnx("initialized EKF state with GPS");
- warnx("vN: %8.4f, vE: %8.4f, vD: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f",
- double(vN), double(vE), double(vD),
- lat, lon, double(alt));
- }
-
- // prediction step
- // using sensors timestamp so we can account for packet lag
- float dt = (_sensors.timestamp - _predictTimeStamp) / 1.0e6f;
- //printf("dt: %15.10f\n", double(dt));
- _predictTimeStamp = _sensors.timestamp;
-
- // don't predict if time greater than a second
- if (dt < 1.0f) {
- predictState(dt);
- predictStateCovariance(dt);
- // count fast frames
- _navFrames += 1;
- }
-
- // count times 100 Hz rate isn't met
- if (dt > 0.01f) _miss++;
-
- // gps correction step
- if (_positionInitialized && gpsUpdate) {
- correctPos();
- }
-
- // attitude correction step
- if (_attitudeInitialized // initialized
- && sensorsUpdate // new data
- && _sensors.timestamp - _attTimeStamp > 1e6 / 50 // 50 Hz
- ) {
- _attTimeStamp = _sensors.timestamp;
- correctAtt();
- }
-
- // publication
- if (newTimeStamp - _pubTimeStamp > 1e6 / 50) { // 50 Hz
- _pubTimeStamp = newTimeStamp;
-
- updatePublications();
- }
-
- // output
- if (newTimeStamp - _outTimeStamp > 10e6) { // 0.1 Hz
- _outTimeStamp = newTimeStamp;
- //printf("nav: %4d Hz, miss #: %4d\n",
- // _navFrames / 10, _miss / 10);
- _navFrames = 0;
- _miss = 0;
- }
-}
-
-void KalmanNav::updatePublications()
-{
- using namespace math;
-
- // global position publication
- _pos.timestamp = _pubTimeStamp;
- _pos.time_gps_usec = _gps.timestamp_position;
- _pos.lat = lat * M_RAD_TO_DEG;
- _pos.lon = lon * M_RAD_TO_DEG;
- _pos.alt = float(alt);
- _pos.vel_n = vN;
- _pos.vel_e = vE;
- _pos.vel_d = vD;
- _pos.yaw = psi;
-
- // local position publication
- float x;
- float y;
- bool landed = alt < (alt0 + 0.1); // XXX improve?
- map_projection_project(&ref, lat, lon, &x, &y);
- _localPos.timestamp = _pubTimeStamp;
- _localPos.xy_valid = true;
- _localPos.z_valid = true;
- _localPos.v_xy_valid = true;
- _localPos.v_z_valid = true;
- _localPos.x = x;
- _localPos.y = y;
- _localPos.z = alt0 - alt;
- _localPos.vx = vN;
- _localPos.vy = vE;
- _localPos.vz = vD;
- _localPos.yaw = psi;
- _localPos.xy_global = true;
- _localPos.z_global = true;
- _localPos.ref_timestamp = _pubTimeStamp;
- _localPos.ref_lat = lat * M_RAD_TO_DEG;
- _localPos.ref_lon = lon * M_RAD_TO_DEG;
- _localPos.ref_alt = 0;
- _localPos.landed = landed;
-
- // attitude publication
- _att.timestamp = _pubTimeStamp;
- _att.roll = phi;
- _att.pitch = theta;
- _att.yaw = psi;
- _att.rollspeed = _sensors.gyro_rad_s[0];
- _att.pitchspeed = _sensors.gyro_rad_s[1];
- _att.yawspeed = _sensors.gyro_rad_s[2];
- // TODO, add gyro offsets to filter
- _att.rate_offsets[0] = 0.0f;
- _att.rate_offsets[1] = 0.0f;
- _att.rate_offsets[2] = 0.0f;
-
- for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
- _att.R[i][j] = C_nb(i, j);
-
- for (int i = 0; i < 4; i++) _att.q[i] = q(i);
-
- _att.R_valid = true;
- _att.q_valid = true;
-
- // selectively update publications,
- // do NOT call superblock do-all method
- if (_positionInitialized) {
- _pos.update();
- _localPos.update();
- }
-
- if (_attitudeInitialized)
- _att.update();
-}
-
-int KalmanNav::predictState(float dt)
-{
- using namespace math;
-
- // trig
- float sinL = sinf(lat);
- float cosL = cosf(lat);
- float cosLSing = cosf(lat);
-
- // prevent singularity
- if (fabsf(cosLSing) < 0.01f) {
- if (cosLSing > 0) cosLSing = 0.01;
- else cosLSing = -0.01;
- }
-
- // attitude prediction
- if (_attitudeInitialized) {
- Vector<3> w(_sensors.gyro_rad_s);
-
- // attitude
- q = q + q.derivative(w) * dt;
-
- // renormalize quaternion if needed
- if (fabsf(q.length() - 1.0f) > 1e-4f) {
- q.normalize();
- }
-
- // C_nb update
- C_nb = q.to_dcm();
-
- // euler update
- Vector<3> euler = C_nb.to_euler();
- phi = euler.data[0];
- theta = euler.data[1];
- psi = euler.data[2];
-
- // specific acceleration in nav frame
- Vector<3> accelB(_sensors.accelerometer_m_s2);
- Vector<3> accelN = C_nb * accelB;
- fN = accelN(0);
- fE = accelN(1);
- fD = accelN(2);
- }
-
- // position prediction
- if (_positionInitialized) {
- // neglects angular deflections in local gravity
- // see Titerton pg. 70
- float R = R0 + float(alt);
- float LDot = vN / R;
- float lDot = vE / (cosLSing * R);
- float rotRate = 2 * omega + lDot;
-
- // XXX position prediction using speed
- float vNDot = fN - vE * rotRate * sinL +
- vD * LDot;
- float vDDot = fD - vE * rotRate * cosL -
- vN * LDot + _g.get();
- float vEDot = fE + vN * rotRate * sinL +
- vDDot * rotRate * cosL;
-
- // rectangular integration
- vN += vNDot * dt;
- vE += vEDot * dt;
- vD += vDDot * dt;
- lat += double(LDot * dt);
- lon += double(lDot * dt);
- alt += double(-vD * dt);
- }
-
- return ret_ok;
-}
-
-int KalmanNav::predictStateCovariance(float dt)
-{
- using namespace math;
-
- // trig
- float sinL = sinf(lat);
- float cosL = cosf(lat);
- float cosLSq = cosL * cosL;
- float tanL = tanf(lat);
-
- // prepare for matrix
- float R = R0 + float(alt);
- float RSq = R * R;
-
- // F Matrix
- // Titterton pg. 291
-
- F(0, 1) = -(omega * sinL + vE * tanL / R);
- F(0, 2) = vN / R;
- F(0, 4) = 1.0f / R;
- F(0, 6) = -omega * sinL;
- F(0, 8) = -vE / RSq;
-
- F(1, 0) = omega * sinL + vE * tanL / R;
- F(1, 2) = omega * cosL + vE / R;
- F(1, 3) = -1.0f / R;
- F(1, 8) = vN / RSq;
-
- F(2, 0) = -vN / R;
- F(2, 1) = -omega * cosL - vE / R;
- F(2, 4) = -tanL / R;
- F(2, 6) = -omega * cosL - vE / (R * cosLSq);
- F(2, 8) = vE * tanL / RSq;
-
- F(3, 1) = -fD;
- F(3, 2) = fE;
- F(3, 3) = vD / R;
- F(3, 4) = -2 * (omega * sinL + vE * tanL / R);
- F(3, 5) = vN / R;
- F(3, 6) = -vE * (2 * omega * cosL + vE / (R * cosLSq));
- F(3, 8) = (vE * vE * tanL - vN * vD) / RSq;
-
- F(4, 0) = fD;
- F(4, 2) = -fN;
- F(4, 3) = 2 * omega * sinL + vE * tanL / R;
- F(4, 4) = (vN * tanL + vD) / R;
- F(4, 5) = 2 * omega * cosL + vE / R;
- F(4, 6) = 2 * omega * (vN * cosL - vD * sinL) +
- vN * vE / (R * cosLSq);
- F(4, 8) = -vE * (vN * tanL + vD) / RSq;
-
- F(5, 0) = -fE;
- F(5, 1) = fN;
- F(5, 3) = -2 * vN / R;
- F(5, 4) = -2 * (omega * cosL + vE / R);
- F(5, 6) = 2 * omega * vE * sinL;
- F(5, 8) = (vN * vN + vE * vE) / RSq;
-
- F(6, 3) = 1 / R;
- F(6, 8) = -vN / RSq;
-
- F(7, 4) = 1 / (R * cosL);
- F(7, 6) = vE * tanL / (R * cosL);
- F(7, 8) = -vE / (cosL * RSq);
-
- F(8, 5) = -1;
-
- // G Matrix
- // Titterton pg. 291
- G(0, 0) = -C_nb(0, 0);
- G(0, 1) = -C_nb(0, 1);
- G(0, 2) = -C_nb(0, 2);
- G(1, 0) = -C_nb(1, 0);
- G(1, 1) = -C_nb(1, 1);
- G(1, 2) = -C_nb(1, 2);
- G(2, 0) = -C_nb(2, 0);
- G(2, 1) = -C_nb(2, 1);
- G(2, 2) = -C_nb(2, 2);
-
- G(3, 3) = C_nb(0, 0);
- G(3, 4) = C_nb(0, 1);
- G(3, 5) = C_nb(0, 2);
- G(4, 3) = C_nb(1, 0);
- G(4, 4) = C_nb(1, 1);
- G(4, 5) = C_nb(1, 2);
- G(5, 3) = C_nb(2, 0);
- G(5, 4) = C_nb(2, 1);
- G(5, 5) = C_nb(2, 2);
-
- // continuous prediction equations
- // for discrete time EKF
- // http://en.wikipedia.org/wiki/Extended_Kalman_filter
- P = P + (F * P + P * F.transposed() + G * V * G.transposed()) * dt;
-
- return ret_ok;
-}
-
-int KalmanNav::correctAtt()
-{
- using namespace math;
-
- // trig
- float cosPhi = cosf(phi);
- float cosTheta = cosf(theta);
- // float cosPsi = cosf(psi);
- float sinPhi = sinf(phi);
- float sinTheta = sinf(theta);
- // float sinPsi = sinf(psi);
-
- // mag predicted measurement
- // choosing some typical magnetic field properties,
- // TODO dip/dec depend on lat/ lon/ time
- //float dip = _magDip.get() / M_RAD_TO_DEG_F; // dip, inclination with level
- float dec = _magDec.get() / M_RAD_TO_DEG_F; // declination, clockwise rotation from north
-
- // compensate roll and pitch, but not yaw
- // XXX take the vectors out of the C_nb matrix to avoid singularities
- math::Matrix<3,3> C_rp;
- C_rp.from_euler(phi, theta, 0.0f);//C_nb.transposed();
-
- // mag measurement
- Vector<3> magBody(_sensors.magnetometer_ga);
-
- // transform to earth frame
- Vector<3> magNav = C_rp * magBody;
-
- // calculate error between estimate and measurement
- // apply declination correction for true heading as well.
- float yMag = -atan2f(magNav(1),magNav(0)) - psi - dec;
- if (yMag > M_PI_F) yMag -= 2*M_PI_F;
- if (yMag < -M_PI_F) yMag += 2*M_PI_F;
-
- // accel measurement
- Vector<3> zAccel(_sensors.accelerometer_m_s2);
- float accelMag = zAccel.length();
- zAccel.normalize();
-
- // ignore accel correction when accel mag not close to g
- Matrix<4,4> RAttAdjust = RAtt;
-
- bool ignoreAccel = fabsf(accelMag - _g.get()) > 1.1f;
-
- if (ignoreAccel) {
- RAttAdjust(1, 1) = 1.0e10;
- RAttAdjust(2, 2) = 1.0e10;
- RAttAdjust(3, 3) = 1.0e10;
-
- } else {
- //printf("correcting attitude with accel\n");
- }
-
- // accel predicted measurement
- Vector<3> zAccelHat = (C_nb.transposed() * Vector<3>(0, 0, -_g.get())).normalized();
-
- // calculate residual
- Vector<4> y(yMag, zAccel(0) - zAccelHat(0), zAccel(1) - zAccelHat(1), zAccel(2) - zAccelHat(2));
-
- // HMag
- HAtt(0, 2) = 1;
-
- // HAccel
- HAtt(1, 1) = cosTheta;
- HAtt(2, 0) = -cosPhi * cosTheta;
- HAtt(2, 1) = sinPhi * sinTheta;
- HAtt(3, 0) = sinPhi * cosTheta;
- HAtt(3, 1) = cosPhi * sinTheta;
-
- // compute correction
- // http://en.wikipedia.org/wiki/Extended_Kalman_filter
- Matrix<4, 4> S = HAtt * P * HAtt.transposed() + RAttAdjust; // residual covariance
- Matrix<9, 4> K = P * HAtt.transposed() * S.inversed();
- Vector<9> xCorrect = K * y;
-
- // check correciton is sane
- for (size_t i = 0; i < xCorrect.get_size(); i++) {
- float val = xCorrect(i);
-
- if (isnan(val) || isinf(val)) {
- // abort correction and return
- warnx("numerical failure in att correction");
- // reset P matrix to P0
- P = P0;
- return ret_error;
- }
- }
-
- // correct state
- if (!ignoreAccel) {
- phi += xCorrect(PHI);
- theta += xCorrect(THETA);
- }
-
- psi += xCorrect(PSI);
-
- // attitude also affects nav velocities
- if (_positionInitialized) {
- vN += xCorrect(VN);
- vE += xCorrect(VE);
- vD += xCorrect(VD);
- }
-
- // update state covariance
- // http://en.wikipedia.org/wiki/Extended_Kalman_filter
- P = P - K * HAtt * P;
-
- // fault detection
- float beta = y * (S.inversed() * y);
-
- if (beta > _faultAtt.get()) {
- warnx("fault in attitude: beta = %8.4f", (double)beta);
- warnx("y:"); y.print();
- }
-
- // update quaternions from euler
- // angle correction
- q.from_euler(phi, theta, psi);
-
- return ret_ok;
-}
-
-int KalmanNav::correctPos()
-{
- using namespace math;
-
- // residual
- Vector<6> y;
- y(0) = _gps.vel_n_m_s - vN;
- y(1) = _gps.vel_e_m_s - vE;
- y(2) = double(_gps.lat) - double(lat) * 1.0e7 * M_RAD_TO_DEG;
- y(3) = double(_gps.lon) - double(lon) * 1.0e7 * M_RAD_TO_DEG;
- y(4) = _gps.alt / 1.0e3f - alt;
- y(5) = _sensors.baro_alt_meter - alt;
-
- // compute correction
- // http://en.wikipedia.org/wiki/Extended_Kalman_filter
- Matrix<6,6> S = HPos * P * HPos.transposed() + RPos; // residual covariance
- Matrix<9,6> K = P * HPos.transposed() * S.inversed();
- Vector<9> xCorrect = K * y;
-
- // check correction is sane
- for (size_t i = 0; i < xCorrect.get_size(); i++) {
- float val = xCorrect(i);
-
- if (!isfinite(val)) {
- // abort correction and return
- warnx("numerical failure in gps correction");
- // fallback to GPS
- vN = _gps.vel_n_m_s;
- vE = _gps.vel_e_m_s;
- vD = _gps.vel_d_m_s;
- setLatDegE7(_gps.lat);
- setLonDegE7(_gps.lon);
- setAltE3(_gps.alt);
- // reset P matrix to P0
- P = P0;
- return ret_error;
- }
- }
-
- // correct state
- vN += xCorrect(VN);
- vE += xCorrect(VE);
- vD += xCorrect(VD);
- lat += double(xCorrect(LAT));
- lon += double(xCorrect(LON));
- alt += xCorrect(ALT);
-
- // update state covariance
- // http://en.wikipedia.org/wiki/Extended_Kalman_filter
- P = P - K * HPos * P;
-
- // fault detetcion
- float beta = y * (S.inversed() * y);
-
- static int counter = 0;
- if (beta > _faultPos.get() && (counter % 10 == 0)) {
- warnx("fault in gps: beta = %8.4f", (double)beta);
- warnx("Y/N: vN: %8.4f, vE: %8.4f, lat: %8.4f, lon: %8.4f, alt: %8.4f, baro: %8.4f",
- double(y(0) / sqrtf(RPos(0, 0))),
- double(y(1) / sqrtf(RPos(1, 1))),
- double(y(2) / sqrtf(RPos(2, 2))),
- double(y(3) / sqrtf(RPos(3, 3))),
- double(y(4) / sqrtf(RPos(4, 4))),
- double(y(5) / sqrtf(RPos(5, 5))));
- }
- counter++;
-
- return ret_ok;
-}
-
-void KalmanNav::updateParams()
-{
- using namespace math;
- using namespace control;
- SuperBlock::updateParams();
-
- // gyro noise
- V(0, 0) = _vGyro.get(); // gyro x, rad/s
- V(1, 1) = _vGyro.get(); // gyro y
- V(2, 2) = _vGyro.get(); // gyro z
-
- // accel noise
- V(3, 3) = _vAccel.get(); // accel x, m/s^2
- V(4, 4) = _vAccel.get(); // accel y
- V(5, 5) = _vAccel.get(); // accel z
-
- // magnetometer noise
- float noiseMin = 1e-6f;
- float noiseMagSq = _rMag.get() * _rMag.get();
-
- if (noiseMagSq < noiseMin) noiseMagSq = noiseMin;
-
- RAtt(0, 0) = noiseMagSq; // normalized direction
-
- // accelerometer noise
- float noiseAccelSq = _rAccel.get() * _rAccel.get();
-
- // bound noise to prevent singularities
- if (noiseAccelSq < noiseMin) noiseAccelSq = noiseMin;
-
- RAtt(1, 1) = noiseAccelSq; // normalized direction
- RAtt(2, 2) = noiseAccelSq;
- RAtt(3, 3) = noiseAccelSq;
-
- // gps noise
- float R = R0 + float(alt);
- float cosLSing = cosf(lat);
-
- // prevent singularity
- if (fabsf(cosLSing) < 0.01f) {
- if (cosLSing > 0) cosLSing = 0.01;
- else cosLSing = -0.01;
- }
-
- float noiseVel = _rGpsVel.get();
- float noiseLatDegE7 = 1.0e7f * M_RAD_TO_DEG_F * _rGpsPos.get() / R;
- float noiseLonDegE7 = noiseLatDegE7 / cosLSing;
- float noiseGpsAlt = _rGpsAlt.get();
- float noisePressAlt = _rPressAlt.get();
-
- // bound noise to prevent singularities
- if (noiseVel < noiseMin) noiseVel = noiseMin;
-
- if (noiseLatDegE7 < noiseMin) noiseLatDegE7 = noiseMin;
-
- if (noiseLonDegE7 < noiseMin) noiseLonDegE7 = noiseMin;
-
- if (noiseGpsAlt < noiseMin) noiseGpsAlt = noiseMin;
-
- if (noisePressAlt < noiseMin) noisePressAlt = noiseMin;
-
- RPos(0, 0) = noiseVel * noiseVel; // vn
- RPos(1, 1) = noiseVel * noiseVel; // ve
- RPos(2, 2) = noiseLatDegE7 * noiseLatDegE7; // lat
- RPos(3, 3) = noiseLonDegE7 * noiseLonDegE7; // lon
- RPos(4, 4) = noiseGpsAlt * noiseGpsAlt; // h
- RPos(5, 5) = noisePressAlt * noisePressAlt; // h
- // XXX, note that RPos depends on lat, so updateParams should
- // be called if lat changes significantly
-}
diff --git a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp b/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
deleted file mode 100644
index 24df153cb..000000000
--- a/src/modules/att_pos_estimator_ekf/KalmanNav.hpp
+++ /dev/null
@@ -1,194 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file KalmanNav.hpp
- *
- * kalman filter navigation code
- */
-
-#pragma once
-
-//#define MATRIX_ASSERT
-//#define VECTOR_ASSERT
-
-#include <nuttx/config.h>
-
-#include <mathlib/mathlib.h>
-#include <controllib/blocks.hpp>
-#include <controllib/block/BlockParam.hpp>
-#include <uORB/Subscription.hpp>
-#include <uORB/Publication.hpp>
-#include <lib/geo/geo.h>
-
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <uORB/topics/parameter_update.h>
-
-#include <drivers/drv_accel.h>
-#include <drivers/drv_gyro.h>
-#include <drivers/drv_mag.h>
-
-#include <drivers/drv_hrt.h>
-#include <poll.h>
-#include <unistd.h>
-
-/**
- * Kalman filter navigation class
- * http://en.wikipedia.org/wiki/Extended_Kalman_filter
- * Discrete-time extended Kalman filter
- */
-class KalmanNav : public control::SuperBlock
-{
-public:
- /**
- * Constructor
- */
- KalmanNav(SuperBlock *parent, const char *name);
-
- /**
- * Deconstuctor
- */
-
- virtual ~KalmanNav() {};
-
- math::Quaternion init(float ax, float ay, float az, float mx, float my, float mz);
-
- /**
- * The main callback function for the class
- */
- void update();
-
-
- /**
- * Publication update
- */
- virtual void updatePublications();
-
- /**
- * State prediction
- * Continuous, non-linear
- */
- int predictState(float dt);
-
- /**
- * State covariance prediction
- * Continuous, linear
- */
- int predictStateCovariance(float dt);
-
- /**
- * Attitude correction
- */
- int correctAtt();
-
- /**
- * Position correction
- */
- int correctPos();
-
- /**
- * Overloaded update parameters
- */
- virtual void updateParams();
-protected:
- // kalman filter
- math::Matrix<9,9> F; /**< Jacobian(f,x), where dx/dt = f(x,u) */
- math::Matrix<9,6> G; /**< noise shaping matrix for gyro/accel */
- math::Matrix<9,9> P; /**< state covariance matrix */
- math::Matrix<9,9> P0; /**< initial state covariance matrix */
- math::Matrix<6,6> V; /**< gyro/ accel noise matrix */
- math::Matrix<4,9> HAtt; /**< attitude measurement matrix */
- math::Matrix<4,4> RAtt; /**< attitude measurement noise matrix */
- math::Matrix<6,9> HPos; /**< position measurement jacobian matrix */
- math::Matrix<6,6> RPos; /**< position measurement noise matrix */
- // attitude
- math::Matrix<3,3> C_nb; /**< direction cosine matrix from body to nav frame */
- math::Quaternion q; /**< quaternion from body to nav frame */
- // subscriptions
- uORB::Subscription<sensor_combined_s> _sensors; /**< sensors sub. */
- uORB::Subscription<vehicle_gps_position_s> _gps; /**< gps sub. */
- uORB::Subscription<parameter_update_s> _param_update; /**< parameter update sub. */
- // publications
- uORB::Publication<vehicle_global_position_s> _pos; /**< position pub. */
- uORB::Publication<vehicle_local_position_s> _localPos; /**< local position pub. */
- uORB::Publication<vehicle_attitude_s> _att; /**< attitude pub. */
- // time stamps
- uint64_t _pubTimeStamp; /**< output data publication time stamp */
- uint64_t _predictTimeStamp; /**< prediction time stamp */
- uint64_t _attTimeStamp; /**< attitude correction time stamp */
- uint64_t _outTimeStamp; /**< output time stamp */
- // frame count
- uint16_t _navFrames; /**< navigation frames completed in output cycle */
- // miss counts
- uint16_t _miss; /**< number of times fast prediction loop missed */
- // accelerations
- float fN, fE, fD; /**< navigation frame acceleration */
- // states
- enum {PHI = 0, THETA, PSI, VN, VE, VD, LAT, LON, ALT}; /**< state enumeration */
- float phi, theta, psi; /**< 3-2-1 euler angles */
- float vN, vE, vD; /**< navigation velocity, m/s */
- double lat, lon; /**< lat, lon radians */
- // parameters
- float alt; /**< altitude, meters */
- double lat0, lon0; /**< reference latitude and longitude */
- struct map_projection_reference_s ref; /**< local projection reference */
- float alt0; /**< refeerence altitude (ground height) */
- control::BlockParamFloat _vGyro; /**< gyro process noise */
- control::BlockParamFloat _vAccel; /**< accelerometer process noise */
- control::BlockParamFloat _rMag; /**< magnetometer measurement noise */
- control::BlockParamFloat _rGpsVel; /**< gps velocity measurement noise */
- control::BlockParamFloat _rGpsPos; /**< gps position measurement noise */
- control::BlockParamFloat _rGpsAlt; /**< gps altitude measurement noise */
- control::BlockParamFloat _rPressAlt; /**< press altitude measurement noise */
- control::BlockParamFloat _rAccel; /**< accelerometer measurement noise */
- control::BlockParamFloat _magDip; /**< magnetic inclination with level */
- control::BlockParamFloat _magDec; /**< magnetic declination, clockwise rotation */
- control::BlockParamFloat _g; /**< gravitational constant */
- control::BlockParamFloat _faultPos; /**< fault detection threshold for position */
- control::BlockParamFloat _faultAtt; /**< fault detection threshold for attitude */
- // status
- bool _attitudeInitialized;
- bool _positionInitialized;
- uint16_t _attitudeInitCounter;
- // accessors
- int32_t getLatDegE7() { return int32_t(lat * 1.0e7 * M_RAD_TO_DEG); }
- void setLatDegE7(int32_t val) { lat = val / 1.0e7 / M_RAD_TO_DEG; }
- int32_t getLonDegE7() { return int32_t(lon * 1.0e7 * M_RAD_TO_DEG); }
- void setLonDegE7(int32_t val) { lon = val / 1.0e7 / M_RAD_TO_DEG; }
- int32_t getAltE3() { return int32_t(alt * 1.0e3); }
- void setAltE3(int32_t val) { alt = double(val) / 1.0e3; }
-};
diff --git a/src/modules/att_pos_estimator_ekf/kalman_main.cpp b/src/modules/att_pos_estimator_ekf/kalman_main.cpp
deleted file mode 100644
index 3d20d4d2d..000000000
--- a/src/modules/att_pos_estimator_ekf/kalman_main.cpp
+++ /dev/null
@@ -1,157 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: James Goppert
- *
- * 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 kalman_main.cpp
- * Combined attitude / position estimator.
- *
- * @author James Goppert
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <systemlib/systemlib.h>
-#include <systemlib/param/param.h>
-#include <systemlib/err.h>
-#include <drivers/drv_hrt.h>
-#include <math.h>
-#include "KalmanNav.hpp"
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int daemon_task; /**< Handle of deamon task / thread */
-
-/**
- * Deamon management function.
- */
-extern "C" __EXPORT int att_pos_estimator_ekf_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int kalman_demo_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- warnx("usage: att_pos_estimator_ekf {start|stop|status} [-p <additional params>]");
- exit(1);
-}
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int att_pos_estimator_ekf_main(int argc, char *argv[])
-{
-
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- warnx("already running");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
-
- daemon_task = task_spawn_cmd("att_pos_estimator_ekf",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 30,
- 8192,
- kalman_demo_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("is running\n");
- exit(0);
-
- } else {
- warnx("not started\n");
- exit(1);
- }
-
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int kalman_demo_thread_main(int argc, char *argv[])
-{
-
- warnx("starting");
-
- using namespace math;
-
- thread_running = true;
-
- KalmanNav nav(NULL, "KF");
-
- while (!thread_should_exit) {
- nav.update();
- }
-
- warnx("exiting.");
-
- thread_running = false;
-
- return 0;
-}
diff --git a/src/modules/att_pos_estimator_ekf/module.mk b/src/modules/att_pos_estimator_ekf/module.mk
deleted file mode 100644
index 8d4a40d95..000000000
--- a/src/modules/att_pos_estimator_ekf/module.mk
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Full attitude / position Extended Kalman Filter
-#
-
-MODULE_COMMAND = att_pos_estimator_ekf
-
-SRCS = kalman_main.cpp \
- KalmanNav.cpp \
- params.c
diff --git a/src/modules/att_pos_estimator_ekf/params.c b/src/modules/att_pos_estimator_ekf/params.c
deleted file mode 100644
index 4af5edead..000000000
--- a/src/modules/att_pos_estimator_ekf/params.c
+++ /dev/null
@@ -1,49 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#include <systemlib/param/param.h>
-
-/*PARAM_DEFINE_FLOAT(NAME,0.0f);*/
-PARAM_DEFINE_FLOAT(KF_V_GYRO, 0.008f);
-PARAM_DEFINE_FLOAT(KF_V_ACCEL, 1.0f);
-PARAM_DEFINE_FLOAT(KF_R_MAG, 0.8f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_VEL, 0.5f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_POS, 2.0f);
-PARAM_DEFINE_FLOAT(KF_R_GPS_ALT, 3.0f);
-PARAM_DEFINE_FLOAT(KF_R_PRESS_ALT, 0.1f);
-PARAM_DEFINE_FLOAT(KF_R_ACCEL, 1.0f);
-PARAM_DEFINE_FLOAT(KF_FAULT_POS, 10.0f);
-PARAM_DEFINE_FLOAT(KF_FAULT_ATT, 10.0f);
-PARAM_DEFINE_FLOAT(KF_ENV_G, 9.765f);
-PARAM_DEFINE_FLOAT(KF_ENV_MAG_DIP, 60.0f);
-PARAM_DEFINE_FLOAT(KF_ENV_MAG_DEC, 0.0f);
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 c61b6ff3f..66a949af1 100755
--- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
+++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,9 +32,12 @@
****************************************************************************/
/*
- * @file attitude_estimator_ekf_main.c
+ * @file attitude_estimator_ekf_main.cpp
*
* Extended Kalman Filter for Attitude Estimation.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
@@ -111,7 +112,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_create().
+ * to task_spawn_cmd().
*/
int attitude_estimator_ekf_main(int argc, char *argv[])
{
@@ -265,7 +266,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
int loopcounter = 0;
- int printcounter = 0;
thread_running = true;
@@ -273,9 +273,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
// struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
// orb_advert_t pub_dbg = -1;
- float sensor_update_hz[3] = {0.0f, 0.0f, 0.0f};
- // XXX write this out to perf regs
-
/* keep track of sensor updates */
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
@@ -286,11 +283,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* initialize parameter handles */
parameters_init(&ekf_param_handles);
- uint64_t start_time = hrt_absolute_time();
bool initialized = false;
float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f };
- unsigned offset_count = 0;
/* rotation matrix for magnetic declination */
math::Matrix<3, 3> R_decl;
@@ -381,7 +376,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* Fill in gyro measurements */
if (sensor_last_timestamp[0] != raw.timestamp) {
update_vect[0] = 1;
- sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
+ // sensor_update_hz[0] = 1e6f / (raw.timestamp - sensor_last_timestamp[0]);
sensor_last_timestamp[0] = raw.timestamp;
}
@@ -392,7 +387,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update accelerometer measurements */
if (sensor_last_timestamp[1] != raw.accelerometer_timestamp) {
update_vect[1] = 1;
- sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
+ // sensor_update_hz[1] = 1e6f / (raw.timestamp - sensor_last_timestamp[1]);
sensor_last_timestamp[1] = raw.accelerometer_timestamp;
}
@@ -444,7 +439,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
/* update magnetometer measurements */
if (sensor_last_timestamp[2] != raw.magnetometer_timestamp) {
update_vect[2] = 1;
- sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
+ // sensor_update_hz[2] = 1e6f / (raw.timestamp - sensor_last_timestamp[2]);
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
}
@@ -497,8 +492,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
continue;
}
- uint64_t timing_start = hrt_absolute_time();
-
attitudeKalmanfilter(update_vect, dt, z_k, x_aposteriori_k, P_aposteriori_k, ekf_params.q, ekf_params.r,
euler, Rot_matrix, x_aposteriori, P_aposteriori);
diff --git a/src/modules/attitude_estimator_ekf/module.mk b/src/modules/attitude_estimator_ekf/module.mk
index d98647f99..99d0c5bf2 100644
--- a/src/modules/attitude_estimator_ekf/module.mk
+++ b/src/modules/attitude_estimator_ekf/module.mk
@@ -50,3 +50,5 @@ SRCS = attitude_estimator_ekf_main.cpp \
codegen/rtGetNaN.c \
codegen/norm.c \
codegen/cross.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
index 3653defa6..e55b01160 100755
--- a/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
+++ b/src/modules/attitude_estimator_so3/attitude_estimator_so3_main.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * Author: Hyon Lim <limhyon@gmail.com>
- * Anton Babushkin <anton.babushkin@me.com>
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -36,6 +34,9 @@
/*
* @file attitude_estimator_so3_main.cpp
*
+ * @author Hyon Lim <limhyon@gmail.com>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* Implementation of nonlinear complementary filters on the SO(3).
* This code performs attitude estimation by using accelerometer, gyroscopes and magnetometer.
* Result is provided as quaternion, 1-2-3 Euler angle and rotation matrix.
@@ -131,7 +132,7 @@ usage(const char *reason)
* Makefile does only apply to this management task.
*
* The actual stack size should be set in the call
- * to task_create().
+ * to task_spawn_cmd().
*/
int attitude_estimator_so3_main(int argc, char *argv[])
{
diff --git a/src/modules/attitude_estimator_so3/module.mk b/src/modules/attitude_estimator_so3/module.mk
index e29bb16a6..f52715abb 100644
--- a/src/modules/attitude_estimator_so3/module.mk
+++ b/src/modules/attitude_estimator_so3/module.mk
@@ -6,3 +6,5 @@ MODULE_COMMAND = attitude_estimator_so3
SRCS = attitude_estimator_so3_main.cpp \
attitude_estimator_so3_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index 1cbdf9bf8..7180048ff 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -194,13 +194,13 @@ int do_accel_calibration(int mavlink_fd)
int32_t board_rotation_int;
param_get(board_rotation_h, &(board_rotation_int));
enum Rotation board_rotation_id = (enum Rotation)board_rotation_int;
- math::Matrix<3,3> board_rotation;
+ math::Matrix<3, 3> board_rotation;
get_rot_matrix(board_rotation_id, &board_rotation);
- math::Matrix<3,3> board_rotation_t = board_rotation.transposed();
+ math::Matrix<3, 3> board_rotation_t = board_rotation.transposed();
math::Vector<3> accel_offs_vec(&accel_offs[0]);
- math::Vector<3> accel_offs_rotated = board_rotation_t * accel_offs_vec;
- math::Matrix<3,3> accel_T_mat(&accel_T[0][0]);
- math::Matrix<3,3> accel_T_rotated = board_rotation_t * accel_T_mat * board_rotation;
+ math::Vector<3> accel_offs_rotated = board_rotation_t *accel_offs_vec;
+ math::Matrix<3, 3> accel_T_mat(&accel_T[0][0]);
+ math::Matrix<3, 3> accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation;
accel_scale.x_offset = accel_offs_rotated(0);
accel_scale.x_scale = accel_T_rotated(0, 0);
@@ -277,11 +277,13 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
}
- if (old_done_count != done_count)
+ if (old_done_count != done_count) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
+ }
- if (done)
+ if (done) {
break;
+ }
mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s",
(!data_collected[0]) ? "x+ " : "",
@@ -380,11 +382,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
- if (d > still_thr2 * 8.0f)
+ if (d > still_thr2 * 8.0f) {
d = still_thr2 * 8.0f;
+ }
- if (d > accel_disp[i])
+ if (d > accel_disp[i]) {
accel_disp[i] = d;
+ }
}
/* still detector with hysteresis */
@@ -432,33 +436,39 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
if (fabsf(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 0; // [ g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 0; // [ g, 0, 0 ]
+ }
if (fabsf(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 1; // [ -g, 0, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 1; // [ -g, 0, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 2; // [ 0, g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 2; // [ 0, g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr &&
- fabsf(accel_ema[2]) < accel_err_thr)
- return 3; // [ 0, -g, 0 ]
+ fabsf(accel_ema[2]) < accel_err_thr) {
+ return 3; // [ 0, -g, 0 ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr)
- return 4; // [ 0, 0, g ]
+ fabsf(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr) {
+ return 4; // [ 0, 0, g ]
+ }
if (fabsf(accel_ema[0]) < accel_err_thr &&
fabsf(accel_ema[1]) < accel_err_thr &&
- fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr)
- return 5; // [ 0, 0, -g ]
+ fabsf(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr) {
+ return 5; // [ 0, 0, -g ]
+ }
mavlink_log_critical(mavlink_fd, "ERROR: invalid orientation");
@@ -485,8 +495,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
struct sensor_combined_s sensor;
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
- for (int i = 0; i < 3; i++)
+ for (int i = 0; i < 3; i++) {
accel_sum[i] += sensor.accelerometer_m_s2[i];
+ }
count++;
@@ -495,8 +506,9 @@ int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samp
continue;
}
- if (errcount > samples_num / 10)
+ if (errcount > samples_num / 10) {
return ERROR;
+ }
}
for (int i = 0; i < 3; i++) {
@@ -512,8 +524,9 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
- if (det == 0.0f)
- return ERROR; // Singular matrix
+ if (det == 0.0f) {
+ return ERROR; // Singular matrix
+ }
dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det;
dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det;
@@ -549,8 +562,9 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
/* calculate inverse matrix for A */
float mat_A_inv[3][3];
- if (mat_invert3(mat_A, mat_A_inv) != OK)
+ if (mat_invert3(mat_A, mat_A_inv) != OK) {
return ERROR;
+ }
/* copy results to accel_T */
for (int i = 0; i < 3; i++) {
diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp
index c8c7a42e7..5d21d89d0 100644
--- a/src/modules/commander/airspeed_calibration.cpp
+++ b/src/modules/commander/airspeed_calibration.cpp
@@ -82,12 +82,15 @@ int do_airspeed_calibration(int mavlink_fd)
bool paramreset_successful = false;
int fd = open(AIRSPEED_DEVICE_PATH, 0);
+
if (fd > 0) {
if (OK == ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
paramreset_successful = true;
+
} else {
mavlink_log_critical(mavlink_fd, "airspeed offset zero failed");
}
+
close(fd);
}
@@ -112,8 +115,9 @@ int do_airspeed_calibration(int mavlink_fd)
diff_pres_offset += diff_pres.differential_pressure_raw_pa;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else if (poll_ret == 0) {
/* any poll failure for 1s is a reason to abort */
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 53ed34f46..5c0628a16 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -117,9 +117,10 @@ extern struct system_load_s system_load;
#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
-#define POSITION_TIMEOUT 100000 /**< consider the local or global position estimate invalid after 100ms */
-#define RC_TIMEOUT 500000
-#define DIFFPRESS_TIMEOUT 2000000
+#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 DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
#define PRINT_MODE_REJECT_INTERVAL 2000000
@@ -220,7 +221,7 @@ void print_status();
transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos);
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy);
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy);
/**
* Loop that runs at a lower rate and priority for calibration and parameter tasks.
@@ -232,8 +233,9 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
int commander_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
usage("missing command");
+ }
if (!strcmp(argv[1], "start")) {
@@ -247,7 +249,7 @@ int commander_main(int argc, char *argv[])
daemon_task = task_spawn_cmd("commander",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 3000,
+ 2950,
commander_thread_main,
(argv) ? (const char **)&argv[2] : (const char **)NULL);
@@ -260,8 +262,9 @@ int commander_main(int argc, char *argv[])
if (!strcmp(argv[1], "stop")) {
- if (!thread_running)
+ if (!thread_running) {
errx(0, "commander already stopped");
+ }
thread_should_exit = true;
@@ -303,8 +306,9 @@ int commander_main(int argc, char *argv[])
void usage(const char *reason)
{
- if (reason)
+ if (reason) {
fprintf(stderr, "%s\n", reason);
+ }
fprintf(stderr, "usage: daemon {start|stop|status} [-p <additional params>]\n\n");
exit(1);
@@ -363,20 +367,22 @@ void print_status()
static orb_advert_t status_pub;
-transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char* armedBy)
+transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy)
{
- transition_result_t arming_res = TRANSITION_NOT_CHANGED;
-
- // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
- // output appropriate error messages if the state cannot transition.
- arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
- if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
- mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
- } else if (arming_res == TRANSITION_DENIED) {
- tune_negative(true);
- }
-
- return arming_res;
+ transition_result_t arming_res = TRANSITION_NOT_CHANGED;
+
+ // Transition the armed state. By passing mavlink_fd to arming_state_transition it will
+ // output appropriate error messages if the state cannot transition.
+ arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
+
+ if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
+ mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
+
+ } else if (arming_res == TRANSITION_DENIED) {
+ tune_negative(true);
+ }
+
+ return arming_res;
}
bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub)
@@ -416,14 +422,16 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
- if (hil_ret == OK)
+ if (hil_ret == OK) {
ret = true;
+ }
- // Transition the arming state
- arming_res = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command");
+ // 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)
+ if (arming_res == TRANSITION_CHANGED) {
ret = true;
+ }
/* set main state */
transition_result_t main_res = TRANSITION_DENIED;
@@ -434,17 +442,21 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
/* MANUAL */
main_res = main_state_transition(status, MAIN_STATE_MANUAL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) {
- /* SEATBELT */
- main_res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
+ /* ALTCTL */
+ main_res = main_state_transition(status, MAIN_STATE_ALTCTL);
- } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
/* AUTO */
main_res = main_state_transition(status, MAIN_STATE_AUTO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
+ /* ACRO */
+ main_res = main_state_transition(status, MAIN_STATE_ACRO);
}
} else {
@@ -455,8 +467,8 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
} else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) {
if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) {
- /* EASY */
- main_res = main_state_transition(status, MAIN_STATE_EASY);
+ /* POSCTL */
+ main_res = main_state_transition(status, MAIN_STATE_POSCTL);
} else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) {
/* MANUAL */
@@ -465,8 +477,9 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
- if (main_res == TRANSITION_CHANGED)
+ if (main_res == TRANSITION_CHANGED) {
ret = true;
+ }
if (arming_res != TRANSITION_DENIED && main_res != TRANSITION_DENIED) {
result = VEHICLE_CMD_RESULT_ACCEPTED;
@@ -479,19 +492,28 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_COMPONENT_ARM_DISARM: {
- // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
- // We use an float epsilon delta to test float equality.
- if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
+ // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm.
+ // We use an float epsilon delta to test float equality.
+ if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) {
mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1);
- } else {
- transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
- if (arming_res == TRANSITION_DENIED) {
- mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
- result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
- } else {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
- }
- }
+
+ } else {
+
+ // Flick to inair restore first if this comes from an onboard system
+ if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) {
+ status->arming_state = ARMING_STATE_IN_AIR_RESTORE;
+ }
+
+ transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command");
+
+ if (arming_res == TRANSITION_DENIED) {
+ mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd");
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+
+ } else {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ }
+ }
}
break;
@@ -519,7 +541,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
break;
- /* Flight termination */
+ /* Flight termination */
case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command
//XXX: to enable the parachute, a param needs to be set
@@ -539,6 +561,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
case VEHICLE_CMD_DO_SET_HOME: {
bool use_current = cmd->param1 > 0.5f;
+
if (use_current) {
/* use current position */
if (status->condition_global_position_valid) {
@@ -582,6 +605,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
}
break;
+
case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
case VEHICLE_CMD_PREFLIGHT_CALIBRATION:
case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS:
@@ -595,6 +619,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
answer_command(*cmd, VEHICLE_CMD_RESULT_UNSUPPORTED);
break;
}
+
if (result != VEHICLE_CMD_RESULT_UNSUPPORTED) {
/* already warned about unsupported commands in "default" case */
answer_command(*cmd, result);
@@ -628,9 +653,10 @@ int commander_thread_main(int argc, char *argv[])
char *main_states_str[MAIN_STATE_MAX];
main_states_str[0] = "MANUAL";
- main_states_str[1] = "SEATBELT";
- main_states_str[2] = "EASY";
+ main_states_str[1] = "ALTCTL";
+ main_states_str[2] = "POSCTL";
main_states_str[3] = "AUTO";
+ main_states_str[4] = "ACRO";
char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[0] = "INIT";
@@ -722,7 +748,7 @@ int commander_thread_main(int argc, char *argv[])
pthread_attr_t commander_low_prio_attr;
pthread_attr_init(&commander_low_prio_attr);
- pthread_attr_setstacksize(&commander_low_prio_attr, 2992);
+ pthread_attr_setstacksize(&commander_low_prio_attr, 2900);
struct sched_param param;
(void)pthread_attr_getschedparam(&commander_low_prio_attr, &param);
@@ -741,8 +767,9 @@ int commander_thread_main(int argc, char *argv[])
bool low_battery_voltage_actions_done = false;
bool critical_battery_voltage_actions_done = false;
- uint64_t last_idle_time = 0;
- uint64_t start_time = 0;
+ 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;
@@ -771,6 +798,9 @@ int commander_thread_main(int argc, char *argv[])
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
struct vehicle_global_position_s global_position;
memset(&global_position, 0, sizeof(global_position));
+ /* Init EPH and EPV */
+ global_position.eph = 1000.0f;
+ global_position.epv = 1000.0f;
/* Subscribe to local position data */
int local_position_sub = orb_subscribe(ORB_ID(vehicle_local_position));
@@ -873,6 +903,7 @@ int commander_thread_main(int argc, char *argv[])
/* re-check RC calibration */
rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
}
+
/* navigation parameters */
param_get(_param_takeoff_alt, &takeoff_alt);
param_get(_param_enable_parachute, &parachute_enabled);
@@ -913,6 +944,7 @@ int commander_thread_main(int argc, char *argv[])
/* disarm if safety is now on and still armed */
if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) {
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
+
if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed)) {
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch");
}
@@ -930,23 +962,31 @@ int commander_thread_main(int argc, char *argv[])
/* update condition_global_position_valid */
/* hysteresis for EPH/EPV */
bool eph_epv_good;
+
if (status.condition_global_position_valid) {
if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) {
eph_epv_good = false;
+
+ } else {
+ eph_epv_good = true;
}
} else {
if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) {
eph_epv_good = true;
+
+ } else {
+ eph_epv_good = false;
}
}
+
check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed);
/* check if GPS fix is ok */
/* update home position */
if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
home.lat = global_position.lat;
home.lon = global_position.lon;
@@ -977,10 +1017,30 @@ int commander_thread_main(int argc, char *argv[])
}
/* update condition_local_position_valid and condition_local_altitude_valid */
- check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && eph_epv_good, &(status.condition_local_position_valid), &status_changed);
+ /* hysteresis for EPH */
+ bool local_eph_good;
+
+ if (status.condition_global_position_valid) {
+ if (local_position.eph > eph_epv_threshold * 2.0f) {
+ local_eph_good = false;
+
+ } else {
+ local_eph_good = true;
+ }
+
+ } else {
+ if (local_position.eph < eph_epv_threshold) {
+ local_eph_good = true;
+
+ } else {
+ local_eph_good = false;
+ }
+ }
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
static bool published_condition_landed_fw = false;
+
if (status.is_rotary_wing && status.condition_local_altitude_valid) {
if (status.condition_landed != local_position.landed) {
status.condition_landed = local_position.landed;
@@ -994,6 +1054,7 @@ int commander_thread_main(int argc, char *argv[])
mavlink_log_critical(mavlink_fd, "#audio: IN AIR");
}
}
+
} else {
if (!published_condition_landed_fw) {
status.condition_landed = false; // Fixedwing does not have a landing detector currently
@@ -1063,8 +1124,9 @@ int commander_thread_main(int argc, char *argv[])
/* compute system load */
uint64_t interval_runtime = system_load.tasks[0].total_runtime - last_idle_time;
- if (last_idle_time > 0)
- status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ if (last_idle_time > 0) {
+ status.load = 1.0f - ((float)interval_runtime / 1e6f); //system load is time spent in non-idle
+ }
last_idle_time = system_load.tasks[0].total_runtime;
@@ -1140,22 +1202,22 @@ int commander_thread_main(int argc, char *argv[])
status.rc_signal_lost = false;
- transition_result_t res; // store all transitions results here
+ transition_result_t arming_res; // store all transitions results here
/* arm/disarm by RC */
- res = TRANSITION_NOT_CHANGED;
+ arming_res = TRANSITION_NOT_CHANGED;
- /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm
+ /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSIST mode and landed) -> disarm
* do it only for rotary wings */
if (status.is_rotary_wing &&
(status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) &&
- (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) &&
- sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ (status.main_state == MAIN_STATE_MANUAL || status.main_state == MAIN_STATE_ACRO || status.condition_landed) &&
+ sp_man.r < -STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) {
/* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */
arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR);
- res = arming_state_transition(&status, &safety, new_arming_state, &armed);
+ arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed);
stick_off_counter = 0;
} else {
@@ -1168,16 +1230,16 @@ int commander_thread_main(int argc, char *argv[])
/* check if left stick is in lower right position and we're in MANUAL mode -> arm */
if (status.arming_state == ARMING_STATE_STANDBY &&
- sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < 0.1f) {
+ sp_man.r > STICK_ON_OFF_LIMIT && sp_man.z < 0.1f) {
if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) {
if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) {
- print_reject_arm("NOT ARMING: Press safety switch first.");
+ print_reject_arm("#audio: NOT ARMING: Press safety switch first.");
} else if (status.main_state != MAIN_STATE_MANUAL) {
- print_reject_arm("NOT ARMING: Switch to MANUAL mode first.");
+ print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first.");
} else {
- res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
+ arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed);
}
stick_on_counter = 0;
@@ -1190,7 +1252,7 @@ int commander_thread_main(int argc, char *argv[])
stick_on_counter = 0;
}
- if (res == TRANSITION_CHANGED) {
+ if (arming_res == TRANSITION_CHANGED) {
if (status.arming_state == ARMING_STATE_ARMED) {
mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC");
@@ -1198,24 +1260,24 @@ int commander_thread_main(int argc, char *argv[])
mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC");
}
- } else if (res == TRANSITION_DENIED) {
+ } else if (arming_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied");
}
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* recover from failsafe */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
/* evaluate the main state machine according to mode switches */
- res = set_main_state_rc(&status, &sp_man);
+ transition_result_t main_res = set_main_state_rc(&status, &sp_man);
/* play tune on mode change only if armed, blink LED always */
- if (res == TRANSITION_CHANGED) {
+ if (main_res == TRANSITION_CHANGED) {
tune_positive(armed.armed);
- } else if (res == TRANSITION_DENIED) {
+ } else if (main_res == TRANSITION_DENIED) {
/* DENIED here indicates bug in the commander */
mavlink_log_critical(mavlink_fd, "ERROR: main state transition denied");
}
@@ -1228,7 +1290,8 @@ int commander_thread_main(int argc, char *argv[])
status.set_nav_state_timestamp = hrt_absolute_time();
} else {
- /* MISSION switch */
+
+ /* LOITER switch */
if (sp_man.loiter_switch == SWITCH_POS_ON) {
/* stick is in LOITER position */
status.set_nav_state = NAV_STATE_LOITER;
@@ -1240,7 +1303,7 @@ int commander_thread_main(int argc, char *argv[])
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) {
+ 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();
@@ -1257,34 +1320,39 @@ int commander_thread_main(int argc, char *argv[])
if (armed.armed) {
if (status.main_state == MAIN_STATE_AUTO) {
/* check if AUTO mode still allowed */
- transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO);
+ transition_result_t auto_res = main_state_transition(&status, MAIN_STATE_AUTO);
+
+ if (auto_res == TRANSITION_NOT_CHANGED) {
+ last_auto_state_valid = hrt_absolute_time();
+ }
- if (res == TRANSITION_DENIED) {
+ /* 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 */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ auto_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_DENIED) {
+ if (auto_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
}
} else {
/* failsafe for manual modes */
- transition_result_t res = TRANSITION_DENIED;
+ transition_result_t manual_res = TRANSITION_DENIED;
if (!status.condition_landed) {
/* vehicle is not landed, try to perform RTL */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_RTL);
}
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* RTL not allowed (no global position estimate) or not wanted, try LAND */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
+ manual_res = failsafe_state_transition(&status, FAILSAFE_STATE_LAND);
- if (res == TRANSITION_DENIED) {
+ if (manual_res == TRANSITION_DENIED) {
/* LAND not allowed, set TERMINATION state */
- res = failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION);
}
}
}
@@ -1292,14 +1360,14 @@ int commander_thread_main(int argc, char *argv[])
} else {
if (status.failsafe_state != FAILSAFE_STATE_NORMAL) {
/* reset failsafe when disarmed */
- transition_result_t res = failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
+ (void)failsafe_state_transition(&status, FAILSAFE_STATE_NORMAL);
}
}
}
// TODO remove this hack
- /* flight termination in manual mode if assisted switch is on easy position */
- if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch == SWITCH_POS_ON) {
+ /* flight termination in manual mode if assist switch is on POSCTL position */
+ if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.posctl_switch == SWITCH_POS_ON) {
if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) {
tune_positive(armed.armed);
}
@@ -1313,8 +1381,9 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(vehicle_command), cmd_sub, &cmd);
/* handle it */
- if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub))
+ if (handle_command(&status, &safety, &cmd, &armed, &home, &global_position, &home_pub)) {
status_changed = true;
+ }
}
/* check which state machines for changes, clear "changed" flag */
@@ -1331,7 +1400,7 @@ int commander_thread_main(int argc, char *argv[])
/* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */
if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid &&
- (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
+ (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) {
// TODO remove code duplication
home.lat = global_position.lat;
@@ -1339,7 +1408,7 @@ int commander_thread_main(int argc, char *argv[])
home.alt = global_position.alt;
warnx("home: lat = %.7f, lon = %.7f, alt = %.2f ", home.lat, home.lon, (double)home.alt);
- mavlink_log_info(mavlink_fd, "[cmd] home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
+ mavlink_log_info(mavlink_fd, "#audio: home: %.7f, %.7f, %.2f", home.lat, home.lon, (double)home.alt);
/* announce new home position */
if (home_pub > 0) {
@@ -1353,6 +1422,7 @@ int commander_thread_main(int argc, char *argv[])
status.condition_home_position_valid = true;
}
}
+
was_armed = armed.armed;
if (main_state_changed) {
@@ -1516,21 +1586,24 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a
} else if (actuator_armed->ready_to_arm) {
/* ready to arm, blink at 1Hz */
- if (leds_counter % 20 == 0)
+ if (leds_counter % 20 == 0) {
led_toggle(LED_BLUE);
+ }
} else {
/* not ready to arm, blink at 10Hz */
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_BLUE);
+ }
}
#endif
/* give system warnings on error LED, XXX maybe add memory usage warning too */
if (status->load > 0.95f) {
- if (leds_counter % 2 == 0)
+ if (leds_counter % 2 == 0) {
led_toggle(LED_AMBER);
+ }
} else {
led_off(LED_AMBER);
@@ -1551,30 +1624,35 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break;
case SWITCH_POS_OFF: // MANUAL
- res = main_state_transition(status, MAIN_STATE_MANUAL);
+ if (sp_man->acro_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_ACRO);
+
+ } else {
+ res = main_state_transition(status, MAIN_STATE_MANUAL);
+ }
// TRANSITION_DENIED is not possible here
break;
- case SWITCH_POS_MIDDLE: // ASSISTED
- if (sp_man->assisted_switch == SWITCH_POS_ON) {
- res = main_state_transition(status, MAIN_STATE_EASY);
+ case SWITCH_POS_MIDDLE: // ASSIST
+ if (sp_man->posctl_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_POSCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT
- print_reject_mode(status, "EASY");
+ // else fallback to ALTCTL
+ print_reject_mode(status, "POSCTL");
}
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this mode
}
- if (sp_man->assisted_switch != SWITCH_POS_ON) {
- print_reject_mode(status, "SEATBELT");
+ if (sp_man->posctl_switch != SWITCH_POS_ON) {
+ print_reject_mode(status, "ALTCTL");
}
// else fallback to MANUAL
@@ -1589,9 +1667,9 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
break; // changed successfully or already in this state
}
- // else fallback to SEATBELT (EASY likely will not work too)
+ // else fallback to ALTCTL (POSCTL likely will not work too)
print_reject_mode(status, "AUTO");
- res = main_state_transition(status, MAIN_STATE_SEATBELT);
+ res = main_state_transition(status, MAIN_STATE_ALTCTL);
if (res != TRANSITION_DENIED) {
break; // changed successfully or already in this state
@@ -1637,7 +1715,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ALTCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1648,7 +1726,7 @@ set_control_mode()
control_mode.flag_control_velocity_enabled = false;
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
control_mode.flag_control_rates_enabled = true;
@@ -1661,6 +1739,18 @@ set_control_mode()
case MAIN_STATE_AUTO:
navigator_enabled = true;
+ break;
+
+ case MAIN_STATE_ACRO:
+ control_mode.flag_control_manual_enabled = true;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
default:
break;
@@ -1744,7 +1834,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
{
switch (result) {
case VEHICLE_CMD_RESULT_ACCEPTED:
- tune_positive(true);
+ tune_positive(true);
break;
case VEHICLE_CMD_RESULT_DENIED:
@@ -1758,7 +1848,8 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul
break;
case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED:
- mavlink_log_critical(mavlink_fd, "#audio: command temporarily rejected: %u", cmd.command);
+ /* this needs additional hints to the user - so let other messages pass and be spoken */
+ mavlink_log_critical(mavlink_fd, "command temporarily rejected: %u", cmd.command);
tune_negative(true);
break;
@@ -1794,8 +1885,9 @@ void *commander_low_prio_loop(void *arg)
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 200);
/* timed out - periodic check for thread_should_exit, etc. */
- if (pret == 0)
+ if (pret == 0) {
continue;
+ }
/* this is undesirable but not much we can do - might want to flag unhappy status */
if (pret < 0) {
@@ -1810,8 +1902,9 @@ void *commander_low_prio_loop(void *arg)
if (cmd.command == VEHICLE_CMD_DO_SET_MODE ||
cmd.command == VEHICLE_CMD_COMPONENT_ARM_DISARM ||
cmd.command == VEHICLE_CMD_NAV_TAKEOFF ||
- cmd.command == VEHICLE_CMD_DO_SET_SERVO)
+ cmd.command == VEHICLE_CMD_DO_SET_SERVO) {
continue;
+ }
/* only handle low-priority commands here */
switch (cmd.command) {
@@ -1889,6 +1982,7 @@ void *commander_low_prio_loop(void *arg)
/* airspeed calibration */
answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED);
calib_ret = do_airspeed_calibration(mavlink_fd);
+
} else if ((int)(cmd.param4) == 0) {
/* RC calibration ended - have we been in one worth confirming? */
if (status.rc_input_blocked) {
@@ -1903,10 +1997,12 @@ void *commander_low_prio_loop(void *arg)
}
- if (calib_ret == OK)
+ if (calib_ret == OK) {
tune_positive(true);
- else
+
+ } else {
tune_negative(true);
+ }
arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed);
@@ -1926,11 +2022,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters load ERROR");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1946,11 +2044,13 @@ void *commander_low_prio_loop(void *arg)
mavlink_log_critical(mavlink_fd, "#audio: parameters save error");
/* convenience as many parts of NuttX use negative errno */
- if (ret < 0)
+ if (ret < 0) {
ret = -ret;
+ }
- if (ret < 1000)
+ if (ret < 1000) {
mavlink_log_critical(mavlink_fd, "#audio: %s", strerror(ret));
+ }
answer_command(cmd, VEHICLE_CMD_RESULT_FAILED);
}
@@ -1960,8 +2060,8 @@ void *commander_low_prio_loop(void *arg)
}
case VEHICLE_CMD_START_RX_PAIR:
- /* handled in the IO driver */
- break;
+ /* handled in the IO driver */
+ break;
default:
/* don't answer on unsupported commands, it will be done in main loop */
diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp
index fe6c9bfaa..940a04aa1 100644
--- a/src/modules/commander/commander_helper.cpp
+++ b/src/modules/commander/commander_helper.cpp
@@ -113,17 +113,22 @@ void buzzer_deinit()
close(buzzer);
}
-void set_tune(int tune) {
+void set_tune(int tune)
+{
unsigned int new_tune_duration = tune_durations[tune];
+
/* don't interrupt currently playing non-repeating tune by repeating */
if (tune_end == 0 || new_tune_duration != 0 || hrt_absolute_time() > tune_end) {
/* allow interrupting current non-repeating tune by the same tune */
if (tune != tune_current || new_tune_duration != 0) {
ioctl(buzzer, TONE_SET_ALARM, tune);
}
+
tune_current = tune;
+
if (new_tune_duration != 0) {
tune_end = hrt_absolute_time() + new_tune_duration;
+
} else {
tune_end = 0;
}
@@ -138,6 +143,7 @@ void tune_positive(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_GREEN);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_POSITIVE_TUNE);
}
@@ -151,6 +157,7 @@ void tune_neutral(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_WHITE);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEUTRAL_TUNE);
}
@@ -164,6 +171,7 @@ void tune_negative(bool use_buzzer)
blink_msg_end = hrt_absolute_time() + BLINK_MSG_TIME;
rgbled_set_color(RGBLED_COLOR_RED);
rgbled_set_mode(RGBLED_MODE_BLINK_FAST);
+
if (use_buzzer) {
set_tune(TONE_NOTIFY_NEGATIVE_TUNE);
}
@@ -198,16 +206,10 @@ int led_init()
return ERROR;
}
- /* the blue LED is only available on FMUv1 but not FMUv2 */
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
-
- if (ioctl(leds, LED_ON, LED_BLUE)) {
- warnx("Blue LED: ioctl fail\n");
- return ERROR;
- }
-
-#endif
+ /* the blue LED is only available on FMUv1 & AeroCore but not FMUv2 */
+ (void)ioctl(leds, LED_ON, LED_BLUE);
+ /* we consider the amber led mandatory */
if (ioctl(leds, LED_ON, LED_AMBER)) {
warnx("Amber LED: ioctl fail\n");
return ERROR;
@@ -217,11 +219,7 @@ int led_init()
rgbleds = open(RGBLED_DEVICE_PATH, 0);
if (rgbleds == -1) {
-#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
- errx(1, "Unable to open " RGBLED_DEVICE_PATH);
-#else
- warnx("No RGB LED found");
-#endif
+ warnx("No RGB LED found at " RGBLED_DEVICE_PATH);
}
return 0;
@@ -254,22 +252,25 @@ int led_off(int led)
void rgbled_set_color(rgbled_color_t color)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_COLOR, (unsigned long)color);
+ }
}
void rgbled_set_mode(rgbled_mode_t mode)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_MODE, (unsigned long)mode);
+ }
}
void rgbled_set_pattern(rgbled_pattern_t *pattern)
{
- if (rgbleds != -1)
+ if (rgbleds != -1) {
ioctl(rgbleds, RGBLED_SET_PATTERN, (unsigned long)pattern);
+ }
}
float battery_remaining_estimate_voltage(float voltage, float discharged)
@@ -309,6 +310,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged)
if (bat_capacity > 0.0f) {
/* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */
ret = fminf(remaining_voltage, 1.0f - discharged / bat_capacity);
+
} else {
/* else use voltage */
ret = remaining_voltage;
diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
index 8a946543d..ee0d08391 100644
--- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp
+++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp
@@ -317,34 +317,34 @@ bool StateMachineHelperTest::mainStateTransitionTest(void)
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to SEATBELT.
+ // MANUAL to ALTCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = true;
- new_main_state = MAIN_STATE_SEATBELT;
- ut_assert("tranisition: manual to seatbelt",
+ new_main_state = MAIN_STATE_ALTCTL;
+ ut_assert("tranisition: manual to altctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("new state: seatbelt", MAIN_STATE_SEATBELT == current_state.main_state);
+ ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state);
- // MANUAL to SEATBELT, invalid local altitude.
+ // MANUAL to ALTCTRL, invalid local altitude.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_altitude_valid = false;
- new_main_state = MAIN_STATE_SEATBELT;
+ new_main_state = MAIN_STATE_ALTCTL;
ut_assert("no transition: invalid local altitude",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
- // MANUAL to EASY.
+ // MANUAL to POSCTRL.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = true;
- new_main_state = MAIN_STATE_EASY;
- ut_assert("transition: manual to easy",
+ new_main_state = MAIN_STATE_POSCTL;
+ ut_assert("transition: manual to posctrl",
TRANSITION_CHANGED == main_state_transition(&current_state, new_main_state));
- ut_assert("current state: easy", MAIN_STATE_EASY == current_state.main_state);
+ ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state);
- // MANUAL to EASY, invalid local position.
+ // MANUAL to POSCTRL, invalid local position.
current_state.main_state = MAIN_STATE_MANUAL;
current_state.condition_local_position_valid = false;
- new_main_state = MAIN_STATE_EASY;
+ new_main_state = MAIN_STATE_POSCTL;
ut_assert("no transition: invalid position",
TRANSITION_DENIED == main_state_transition(&current_state, new_main_state));
ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state);
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 30cd0d48d..cbc2844c1 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -110,8 +110,9 @@ int do_gyro_calibration(int mavlink_fd)
gyro_scale.z_offset += gyro_report.z;
calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
+ if (calibration_counter % (calibration_count / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+ }
} else {
poll_errcount++;
@@ -163,8 +164,9 @@ int do_gyro_calibration(int mavlink_fd)
/* apply new offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale)) {
warn("WARNING: failed to apply new offsets for gyro");
+ }
close(fd);
@@ -178,9 +180,9 @@ int do_gyro_calibration(int mavlink_fd)
float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+ if (mag_last > M_PI_F) { mag_last -= 2 * M_PI_F; }
- if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
+ if (mag_last < -M_PI_F) { mag_last += 2 * M_PI_F; }
uint64_t last_time = hrt_absolute_time();
@@ -220,15 +222,15 @@ int do_gyro_calibration(int mavlink_fd)
//float mag = -atan2f(magNav(1),magNav(0));
float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2 * M_PI_F;
+ if (mag > M_PI_F) { mag -= 2 * M_PI_F; }
- if (mag < -M_PI_F) mag += 2 * M_PI_F;
+ if (mag < -M_PI_F) { mag += 2 * M_PI_F; }
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2 * M_PI_F;
+ if (diff > M_PI_F) { diff -= 2 * M_PI_F; }
- if (diff < -M_PI_F) diff += 2 * M_PI_F;
+ if (diff < -M_PI_F) { diff += 2 * M_PI_F; }
baseline_integral += diff;
mag_last = mag;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index 4ebf266f4..0ead22f77 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -72,7 +72,7 @@ int do_mag_calibration(int mavlink_fd)
uint64_t calibration_interval = 45 * 1000 * 1000;
/* maximum 500 values */
- const unsigned int calibration_maxcount = 500;
+ const unsigned int calibration_maxcount = 240;
unsigned int calibration_counter;
struct mag_scale mscale_null = {
@@ -121,9 +121,24 @@ int do_mag_calibration(int mavlink_fd)
if (x == NULL || y == NULL || z == NULL) {
mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+
+ /* clean up */
+ if (x != NULL) {
+ free(x);
+ }
+
+ if (y != NULL) {
+ free(y);
+ }
+
+ if (z != NULL) {
+ free(z);
+ }
+
res = ERROR;
return res;
}
+
} else {
/* exit */
return ERROR;
@@ -163,8 +178,9 @@ int do_mag_calibration(int mavlink_fd)
calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
+ if (calibration_counter % (calibration_maxcount / 20) == 0) {
mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ }
} else {
poll_errcount++;
@@ -198,14 +214,17 @@ int do_mag_calibration(int mavlink_fd)
}
}
- if (x != NULL)
+ if (x != NULL) {
free(x);
+ }
- if (y != NULL)
+ if (y != NULL) {
free(y);
+ }
- if (z != NULL)
+ if (z != NULL) {
free(z);
+ }
if (res == OK) {
/* apply calibration and set parameters */
@@ -234,23 +253,29 @@ int do_mag_calibration(int mavlink_fd)
if (res == OK) {
/* set parameters */
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
res = ERROR;
+ }
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
res = ERROR;
+ }
if (res != OK) {
mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk
index 554dfcb08..27ca5c182 100644
--- a/src/modules/commander/module.mk
+++ b/src/modules/commander/module.mk
@@ -47,3 +47,7 @@ SRCS = commander.cpp \
baro_calibration.cpp \
rc_calibration.cpp \
airspeed_calibration.cpp
+
+MODULE_STACKSIZE = 1200
+
+MAXOPTIMIZATION = -Os
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index 2144d3460..e0f8dc95d 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -12,9 +12,10 @@
enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_MANUAL = 1,
- PX4_CUSTOM_MAIN_MODE_SEATBELT,
- PX4_CUSTOM_MAIN_MODE_EASY,
+ PX4_CUSTOM_MAIN_MODE_ALTCTL,
+ PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
+ PX4_CUSTOM_MAIN_MODE_ACRO,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/rc_calibration.cpp b/src/modules/commander/rc_calibration.cpp
index 41f3ca0aa..0776894fb 100644
--- a/src/modules/commander/rc_calibration.cpp
+++ b/src/modules/commander/rc_calibration.cpp
@@ -69,11 +69,11 @@ int do_trim_calibration(int mavlink_fd)
orb_copy(ORB_ID(manual_control_setpoint), sub_man, &sp);
/* set parameters */
- float p = sp.roll;
+ float p = sp.y;
param_set(param_find("TRIM_ROLL"), &p);
- p = sp.pitch;
+ p = sp.x;
param_set(param_find("TRIM_PITCH"), &p);
- p = sp.yaw;
+ p = sp.r;
param_set(param_find("TRIM_YAW"), &p);
/* store to permanent storage */
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index f09d586c7..87309b238 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -75,38 +75,38 @@ static bool failsafe_state_changed = true;
// though the transition is marked as true additional checks must be made. See arming_state_transition
// code for those checks.
static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = {
- // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
- { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
- { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
- { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
- { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
- { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
- { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
- { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
+ // INIT, STANDBY, ARMED, ARMED_ERROR, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
+ { /* ARMING_STATE_INIT */ true, true, false, false, false, false, false },
+ { /* ARMING_STATE_STANDBY */ true, true, true, true, false, false, false },
+ { /* ARMING_STATE_ARMED */ false, true, true, false, false, false, true },
+ { /* ARMING_STATE_ARMED_ERROR */ false, false, true, true, false, false, false },
+ { /* ARMING_STATE_STANDBY_ERROR */ true, true, false, true, true, false, false },
+ { /* ARMING_STATE_REBOOT */ true, true, false, false, true, true, true },
+ { /* ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false, false }, // NYI
};
// You can index into the array with an arming_state_t in order to get it's textual representation
-static const char* state_names[ARMING_STATE_MAX] = {
- "ARMING_STATE_INIT",
- "ARMING_STATE_STANDBY",
- "ARMING_STATE_ARMED",
- "ARMING_STATE_ARMED_ERROR",
- "ARMING_STATE_STANDBY_ERROR",
- "ARMING_STATE_REBOOT",
- "ARMING_STATE_IN_AIR_RESTORE",
+static const char *state_names[ARMING_STATE_MAX] = {
+ "ARMING_STATE_INIT",
+ "ARMING_STATE_STANDBY",
+ "ARMING_STATE_ARMED",
+ "ARMING_STATE_ARMED_ERROR",
+ "ARMING_STATE_STANDBY_ERROR",
+ "ARMING_STATE_REBOOT",
+ "ARMING_STATE_IN_AIR_RESTORE",
};
transition_result_t
arming_state_transition(struct vehicle_status_s *status, /// current vehicle status
- const struct safety_s *safety, /// current safety settings
- arming_state_t new_arming_state, /// arming state requested
- struct actuator_armed_s *armed, /// current armed status
- const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
+ const struct safety_s *safety, /// current safety settings
+ arming_state_t new_arming_state, /// arming state requested
+ struct actuator_armed_s *armed, /// current armed status
+ const int mavlink_fd) /// mavlink fd for error reporting, 0 for none
{
- // Double check that our static arrays are still valid
- ASSERT(ARMING_STATE_INIT == 0);
- ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
-
+ // Double check that our static arrays are still valid
+ ASSERT(ARMING_STATE_INIT == 0);
+ ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1);
+
/*
* Perform an atomic state update
*/
@@ -117,63 +117,70 @@ arming_state_transition(struct vehicle_status_s *status, /// current
/* only check transition if the new state is actually different from the current one */
if (new_arming_state == status->arming_state) {
ret = TRANSITION_NOT_CHANGED;
+
} else {
/* enforce lockdown in HIL */
if (status->hil_state == HIL_STATE_ON) {
armed->lockdown = true;
+
} else {
armed->lockdown = false;
}
-
- // Check that we have a valid state transition
- bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
- if (valid_transition) {
- // We have a good transition. Now perform any secondary validation.
- if (new_arming_state == ARMING_STATE_ARMED) {
- // Fail transition if we need safety switch press
- // Allow if coming from in air restore
- // Allow if HIL_STATE_ON
- if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first.");
- }
- valid_transition = false;
- }
- } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
- new_arming_state = ARMING_STATE_STANDBY_ERROR;
- }
- }
-
- // HIL can always go to standby
- if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
- valid_transition = true;
- }
-
- /* Sensors need to be initialized for STANDBY state */
- if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
- valid_transition = false;
- }
-
- // Finish up the state transition
- if (valid_transition) {
- armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
- armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
- ret = TRANSITION_CHANGED;
- status->arming_state = new_arming_state;
- arming_state_changed = true;
- }
- }
-
+
+ // Check that we have a valid state transition
+ bool valid_transition = arming_transitions[new_arming_state][status->arming_state];
+
+ if (valid_transition) {
+ // We have a good transition. Now perform any secondary validation.
+ if (new_arming_state == ARMING_STATE_ARMED) {
+ // Fail transition if we need safety switch press
+ // Allow if coming from in air restore
+ // Allow if HIL_STATE_ON
+ if (status->arming_state != ARMING_STATE_IN_AIR_RESTORE && status->hil_state == HIL_STATE_OFF && safety->safety_switch_available && !safety->safety_off) {
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch first.");
+ }
+
+ valid_transition = false;
+ }
+
+ } else if (new_arming_state == ARMING_STATE_STANDBY && status->arming_state == ARMING_STATE_ARMED_ERROR) {
+ new_arming_state = ARMING_STATE_STANDBY_ERROR;
+ }
+ }
+
+ // HIL can always go to standby
+ if (status->hil_state == HIL_STATE_ON && new_arming_state == ARMING_STATE_STANDBY) {
+ valid_transition = true;
+ }
+
+ /* Sensors need to be initialized for STANDBY state */
+ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) {
+ valid_transition = false;
+ }
+
+ // Finish up the state transition
+ if (valid_transition) {
+ armed->armed = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_ARMED_ERROR;
+ armed->ready_to_arm = new_arming_state == ARMING_STATE_ARMED || new_arming_state == ARMING_STATE_STANDBY;
+ ret = TRANSITION_CHANGED;
+ status->arming_state = new_arming_state;
+ arming_state_changed = true;
+ }
+ }
+
/* end of atomic state update */
irqrestore(flags);
- if (ret == TRANSITION_DENIED) {
- static const char* errMsg = "Invalid arming transition from %s to %s";
- if (mavlink_fd) {
- mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
- warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
- }
+ if (ret == TRANSITION_DENIED) {
+ static const char *errMsg = "Invalid arming transition from %s to %s";
+
+ if (mavlink_fd) {
+ mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
+
+ warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]);
+ }
return ret;
}
@@ -215,7 +222,11 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
ret = TRANSITION_CHANGED;
break;
- case MAIN_STATE_SEATBELT:
+ case MAIN_STATE_ACRO:
+ ret = TRANSITION_CHANGED;
+ break;
+
+ case MAIN_STATE_ALTCTL:
/* need at minimum altitude estimate */
if (!status->is_rotary_wing ||
@@ -226,7 +237,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
break;
- case MAIN_STATE_EASY:
+ case MAIN_STATE_POSCTL:
/* need at minimum local position estimate */
if (status->condition_local_position_valid ||
@@ -301,7 +312,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
case HIL_STATE_OFF:
/* we're in HIL and unexpected things can happen if we disable HIL now */
- mavlink_log_critical(mavlink_fd, "Not switching off HIL (safety)");
+ mavlink_log_critical(mavlink_fd, "#audio: Not switching off HIL (safety)");
valid_transition = false;
break;
@@ -320,6 +331,7 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
/* list directory */
DIR *d;
d = opendir("/dev");
+
if (d) {
struct dirent *direntry;
@@ -331,26 +343,32 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s
if (!strncmp("tty", direntry->d_name, 3)) {
continue;
}
+
/* skip mtd devices */
if (!strncmp("mtd", direntry->d_name, 3)) {
continue;
}
+
/* skip ram devices */
if (!strncmp("ram", direntry->d_name, 3)) {
continue;
}
+
/* skip MMC devices */
if (!strncmp("mmc", direntry->d_name, 3)) {
continue;
}
+
/* skip mavlink */
if (!strcmp("mavlink", direntry->d_name)) {
continue;
}
+
/* skip console */
if (!strcmp("console", direntry->d_name)) {
continue;
}
+
/* skip null */
if (!strcmp("null", direntry->d_name)) {
continue;
diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c
index 7505ba358..1a65313e8 100644
--- a/src/modules/dataman/dataman.c
+++ b/src/modules/dataman/dataman.c
@@ -1,10 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: Jean Cyr
- * Lorenz Meier
- * Julian Oes
- * Thomas Gubler
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +33,11 @@
/**
* @file dataman.c
* DATAMANAGER driver.
+ *
+ * @author Jean Cyr
+ * @author Lorenz Meier
+ * @author Julian Oes
+ * @author Thomas Gubler
*/
#include <nuttx/config.h>
@@ -62,7 +63,7 @@ __EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t
__EXPORT int dm_clear(dm_item_t item);
__EXPORT int dm_restart(dm_reset_reason restart_type);
-/* Types of function calls supported by the worker task */
+/** Types of function calls supported by the worker task */
typedef enum {
dm_write_func = 0,
dm_read_func,
@@ -71,11 +72,12 @@ typedef enum {
dm_number_of_funcs
} dm_function_t;
-/* Work task work item */
+/** Work task work item */
typedef struct {
sq_entry_t link; /**< list linkage */
sem_t wait_sem;
- dm_function_t func;
+ unsigned char first;
+ unsigned char func;
ssize_t result;
union {
struct {
@@ -100,6 +102,8 @@ typedef struct {
};
} work_q_item_t;
+const size_t k_work_item_allocation_chunk_size = 8;
+
/* Usage statistics */
static unsigned g_func_counts[dm_number_of_funcs];
@@ -177,9 +181,23 @@ create_work_item(void)
unlock_queue(&g_free_q);
- /* If we there weren't any free items then obtain memory for a new one */
- if (item == NULL)
- item = (work_q_item_t *)malloc(sizeof(work_q_item_t));
+ /* If we there weren't any free items then obtain memory for a new ones */
+ if (item == NULL) {
+ item = (work_q_item_t *)malloc(k_work_item_allocation_chunk_size * sizeof(work_q_item_t));
+ if (item) {
+ item->first = 1;
+ lock_queue(&g_free_q);
+ for (int i = 1; i < k_work_item_allocation_chunk_size; i++) {
+ (item + i)->first = 0;
+ sq_addfirst(&(item + i)->link, &(g_free_q.q));
+ }
+ /* Update the queue size and potentially the maximum queue size */
+ g_free_q.size += k_work_item_allocation_chunk_size - 1;
+ if (g_free_q.size > g_free_q.max_size)
+ g_free_q.max_size = g_free_q.size;
+ unlock_queue(&g_free_q);
+ }
+ }
/* If we got one then lock the item*/
if (item)
@@ -411,7 +429,7 @@ _clear(dm_item_t item)
return result;
}
-/* Tell the data manager about the type of the last reset */
+/** Tell the data manager about the type of the last reset */
static int
_restart(dm_reset_reason reason)
{
@@ -480,7 +498,7 @@ _restart(dm_reset_reason reason)
return result;
}
-/* write to the data manager file */
+/** Write to the data manager file */
__EXPORT ssize_t
dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buf, size_t count)
{
@@ -505,7 +523,7 @@ dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const
return (ssize_t)enqueue_work_item_and_wait_for_result(work);
}
-/* Retrieve from the data manager file */
+/** Retrieve from the data manager file */
__EXPORT ssize_t
dm_read(dm_item_t item, unsigned char index, void *buf, size_t count)
{
@@ -717,8 +735,8 @@ task_main(int argc, char *argv[])
for (;;) {
if ((work = (work_q_item_t *)sq_remfirst(&(g_free_q.q))) == NULL)
break;
-
- free(work);
+ if (work->first)
+ free(work);
}
destroy_q(&g_work_q);
@@ -736,7 +754,7 @@ start(void)
sem_init(&g_init_sema, 1, 0);
/* start the worker thread */
- if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, NULL)) <= 0) {
+ if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2000, task_main, NULL)) <= 0) {
warn("task start failed");
return -1;
}
diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h
index 4382baeb5..1dfb26f73 100644
--- a/src/modules/dataman/dataman.h
+++ b/src/modules/dataman/dataman.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -46,7 +46,7 @@
extern "C" {
#endif
- /* Types of items that the data manager can store */
+ /** Types of items that the data manager can store */
typedef enum {
DM_KEY_SAFE_POINTS = 0, /* Safe points coordinates, safe point 0 is home point */
DM_KEY_FENCE_POINTS, /* Fence vertex coordinates */
@@ -56,7 +56,7 @@ extern "C" {
DM_KEY_NUM_KEYS /* Total number of item types defined */
} dm_item_t;
- /* The maximum number of instances for each item type */
+ /** The maximum number of instances for each item type */
enum {
DM_KEY_SAFE_POINTS_MAX = 8,
DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES,
@@ -65,24 +65,24 @@ extern "C" {
DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED
};
- /* Data persistence levels */
+ /** Data persistence levels */
typedef enum {
DM_PERSIST_POWER_ON_RESET = 0, /* Data survives all resets */
DM_PERSIST_IN_FLIGHT_RESET, /* Data survives in-flight resets only */
DM_PERSIST_VOLATILE /* Data does not survive resets */
} dm_persitence_t;
- /* The reason for the last reset */
+ /** The reason for the last reset */
typedef enum {
DM_INIT_REASON_POWER_ON = 0, /* Data survives resets */
DM_INIT_REASON_IN_FLIGHT, /* Data survives in-flight resets only */
DM_INIT_REASON_VOLATILE /* Data does not survive reset */
} dm_reset_reason;
- /* Maximum size in bytes of a single item instance */
+ /** Maximum size in bytes of a single item instance */
#define DM_MAX_DATA_SIZE 124
- /* Retrieve from the data manager store */
+ /** Retrieve from the data manager store */
__EXPORT ssize_t
dm_read(
dm_item_t item, /* The item type to retrieve */
@@ -91,7 +91,7 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
- /* write to the data manager store */
+ /** write to the data manager store */
__EXPORT ssize_t
dm_write(
dm_item_t item, /* The item type to store */
@@ -101,13 +101,13 @@ extern "C" {
size_t buflen /* Length in bytes of data to retrieve */
);
- /* Erase all items of this type */
+ /** Erase all items of this type */
__EXPORT int
dm_clear(
dm_item_t item /* The item type to clear */
);
- /* Tell the data manager about the type of the last reset */
+ /** Tell the data manager about the type of the last reset */
__EXPORT int
dm_restart(
dm_reset_reason restart_type /* The last reset type */
diff --git a/src/modules/dataman/module.mk b/src/modules/dataman/module.mk
index 27670dd3f..234607b3d 100644
--- a/src/modules/dataman/module.mk
+++ b/src/modules/dataman/module.mk
@@ -38,3 +38,5 @@
MODULE_COMMAND = dataman
SRCS = dataman.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index f076c94fd..0a6d3fa8f 100644
--- a/src/modules/fw_att_pos_estimator/fw_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file fw_att_pos_estimator_main.cpp
+ * @file ekf_att_pos_estimator_main.cpp
* Implementation of the attitude and position estimator.
*
* @author Paul Riseborough <p_riseborough@live.com.au>
@@ -73,6 +73,7 @@
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/estimator_status.h>
#include <uORB/topics/actuator_armed.h>
+#include <uORB/topics/home_position.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <geo/geo.h>
@@ -90,20 +91,19 @@
*
* @ingroup apps
*/
-extern "C" __EXPORT int fw_att_pos_estimator_main(int argc, char *argv[]);
+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;
uint32_t millis()
{
return IMUmsec;
}
-static void print_status();
-
class FixedwingEstimator
{
public:
@@ -152,6 +152,7 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _mission_sub;
+ int _home_sub; /**< home position as defined by commander / user */
orb_advert_t _att_pub; /**< vehicle attitude */
orb_advert_t _global_pos_pub; /**< global position */
@@ -191,7 +192,13 @@ private:
perf_counter_t _perf_airspeed; ///<local performance counter for airspeed updates
bool _initialized;
+ bool _baro_init;
bool _gps_initialized;
+ uint64_t _gps_start_time;
+ uint64_t _filter_start_time;
+ bool _gyro_valid;
+ bool _accel_valid;
+ bool _mag_valid;
int _mavlink_fd;
@@ -201,6 +208,19 @@ private:
int32_t height_delay_ms;
int32_t mag_delay_ms;
int32_t tas_delay_ms;
+ float velne_noise;
+ float veld_noise;
+ float posne_noise;
+ float posd_noise;
+ float mag_noise;
+ float gyro_pnoise;
+ float acc_pnoise;
+ float gbias_pnoise;
+ float abias_pnoise;
+ float mage_pnoise;
+ float magb_pnoise;
+ float eas_noise;
+ float pos_stddev_threshold;
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -209,6 +229,19 @@ private:
param_t height_delay_ms;
param_t mag_delay_ms;
param_t tas_delay_ms;
+ param_t velne_noise;
+ param_t veld_noise;
+ param_t posne_noise;
+ param_t posd_noise;
+ param_t mag_noise;
+ param_t gyro_pnoise;
+ param_t acc_pnoise;
+ param_t gbias_pnoise;
+ param_t abias_pnoise;
+ param_t mage_pnoise;
+ param_t magb_pnoise;
+ param_t eas_noise;
+ param_t pos_stddev_threshold;
} _parameter_handles; /**< handles for interesting parameters */
AttPosEKF *_ekf;
@@ -237,7 +270,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace estimator
@@ -271,6 +304,8 @@ FixedwingEstimator::FixedwingEstimator() :
_vstatus_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
+ _mission_sub(-1),
+ _home_sub(-1),
/* publications */
_att_pub(-1),
@@ -278,32 +313,68 @@ FixedwingEstimator::FixedwingEstimator() :
_local_pos_pub(-1),
_estimator_status_pub(-1),
+ _att({}),
+ _gyro({}),
+ _accel({}),
+ _mag({}),
+ _airspeed({}),
+ _baro({}),
+ _vstatus({}),
+ _global_pos({}),
+ _local_pos({}),
+ _gps({}),
+
+ _gyro_offsets({}),
+ _accel_offsets({}),
+ _mag_offsets({}),
+
+ #ifdef SENSOR_COMBINED_SUB
+ _sensor_combined({}),
+ #endif
+
_baro_ref(0.0f),
_baro_gps_offset(0.0f),
/* performance counters */
- _loop_perf(perf_alloc(PC_COUNT, "fw_att_pos_estimator")),
- _perf_gyro(perf_alloc(PC_COUNT, "fw_ekf_gyro_upd")),
- _perf_accel(perf_alloc(PC_COUNT, "fw_ekf_accel_upd")),
- _perf_mag(perf_alloc(PC_COUNT, "fw_ekf_mag_upd")),
- _perf_gps(perf_alloc(PC_COUNT, "fw_ekf_gps_upd")),
- _perf_baro(perf_alloc(PC_COUNT, "fw_ekf_baro_upd")),
- _perf_airspeed(perf_alloc(PC_COUNT, "fw_ekf_aspd_upd")),
+ _loop_perf(perf_alloc(PC_COUNT, "ekf_att_pos_estimator")),
+ _perf_gyro(perf_alloc(PC_COUNT, "ekf_att_pos_gyro_upd")),
+ _perf_accel(perf_alloc(PC_COUNT, "ekf_att_pos_accel_upd")),
+ _perf_mag(perf_alloc(PC_COUNT, "ekf_att_pos_mag_upd")),
+ _perf_gps(perf_alloc(PC_COUNT, "ekf_att_pos_gps_upd")),
+ _perf_baro(perf_alloc(PC_COUNT, "ekf_att_pos_baro_upd")),
+ _perf_airspeed(perf_alloc(PC_COUNT, "ekf_att_pos_aspd_upd")),
/* states */
_initialized(false),
+ _baro_init(false),
_gps_initialized(false),
+ _gyro_valid(false),
+ _accel_valid(false),
+ _mag_valid(false),
_mavlink_fd(-1),
_ekf(nullptr)
{
- _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ 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");
_parameter_handles.height_delay_ms = param_find("PE_HGT_DELAY_MS");
_parameter_handles.mag_delay_ms = param_find("PE_MAG_DELAY_MS");
_parameter_handles.tas_delay_ms = param_find("PE_TAS_DELAY_MS");
+ _parameter_handles.velne_noise = param_find("PE_VELNE_NOISE");
+ _parameter_handles.veld_noise = param_find("PE_VELD_NOISE");
+ _parameter_handles.posne_noise = param_find("PE_POSNE_NOISE");
+ _parameter_handles.posd_noise = param_find("PE_POSD_NOISE");
+ _parameter_handles.mag_noise = param_find("PE_MAG_NOISE");
+ _parameter_handles.gyro_pnoise = param_find("PE_GYRO_PNOISE");
+ _parameter_handles.acc_pnoise = param_find("PE_ACC_PNOISE");
+ _parameter_handles.gbias_pnoise = param_find("PE_GBIAS_PNOISE");
+ _parameter_handles.abias_pnoise = param_find("PE_ABIAS_PNOISE");
+ _parameter_handles.mage_pnoise = param_find("PE_MAGE_PNOISE");
+ _parameter_handles.magb_pnoise = param_find("PE_MAGB_PNOISE");
+ _parameter_handles.eas_noise = param_find("PE_EAS_NOISE");
+ _parameter_handles.pos_stddev_threshold = param_find("PE_POSDEV_INIT");
/* fetch initial parameter values */
parameters_update();
@@ -317,6 +388,10 @@ FixedwingEstimator::FixedwingEstimator() :
if (fd > 0) {
res = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&_gyro_offsets);
close(fd);
+
+ if (res) {
+ warnx("G SCALE FAIL");
+ }
}
fd = open(ACCEL_DEVICE_PATH, O_RDONLY);
@@ -324,6 +399,10 @@ FixedwingEstimator::FixedwingEstimator() :
if (fd > 0) {
res = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&_accel_offsets);
close(fd);
+
+ if (res) {
+ warnx("A SCALE FAIL");
+ }
}
fd = open(MAG_DEVICE_PATH, O_RDONLY);
@@ -331,6 +410,10 @@ FixedwingEstimator::FixedwingEstimator() :
if (fd > 0) {
res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&_mag_offsets);
close(fd);
+
+ if (res) {
+ warnx("M SCALE FAIL");
+ }
}
}
@@ -368,6 +451,37 @@ FixedwingEstimator::parameters_update()
param_get(_parameter_handles.height_delay_ms, &(_parameters.height_delay_ms));
param_get(_parameter_handles.mag_delay_ms, &(_parameters.mag_delay_ms));
param_get(_parameter_handles.tas_delay_ms, &(_parameters.tas_delay_ms));
+ param_get(_parameter_handles.velne_noise, &(_parameters.velne_noise));
+ param_get(_parameter_handles.veld_noise, &(_parameters.veld_noise));
+ param_get(_parameter_handles.posne_noise, &(_parameters.posne_noise));
+ param_get(_parameter_handles.posd_noise, &(_parameters.posd_noise));
+ param_get(_parameter_handles.mag_noise, &(_parameters.mag_noise));
+ param_get(_parameter_handles.gyro_pnoise, &(_parameters.gyro_pnoise));
+ param_get(_parameter_handles.acc_pnoise, &(_parameters.acc_pnoise));
+ param_get(_parameter_handles.gbias_pnoise, &(_parameters.gbias_pnoise));
+ param_get(_parameter_handles.abias_pnoise, &(_parameters.abias_pnoise));
+ param_get(_parameter_handles.mage_pnoise, &(_parameters.mage_pnoise));
+ param_get(_parameter_handles.magb_pnoise, &(_parameters.magb_pnoise));
+ param_get(_parameter_handles.eas_noise, &(_parameters.eas_noise));
+ param_get(_parameter_handles.pos_stddev_threshold, &(_parameters.pos_stddev_threshold));
+
+ if (_ekf) {
+ // _ekf->yawVarScale = 1.0f;
+ // _ekf->windVelSigma = 0.1f;
+ _ekf->dAngBiasSigma = _parameters.gbias_pnoise;
+ _ekf->dVelBiasSigma = _parameters.abias_pnoise;
+ _ekf->magEarthSigma = _parameters.mage_pnoise;
+ _ekf->magBodySigma = _parameters.magb_pnoise;
+ // _ekf->gndHgtSigma = 0.02f;
+ _ekf->vneSigma = _parameters.velne_noise;
+ _ekf->vdSigma = _parameters.veld_noise;
+ _ekf->posNeSigma = _parameters.posne_noise;
+ _ekf->posDSigma = _parameters.posd_noise;
+ _ekf->magMeasurementSigma = _parameters.mag_noise;
+ _ekf->gyroProcessNoise = _parameters.gyro_pnoise;
+ _ekf->accelProcessNoise = _parameters.acc_pnoise;
+ _ekf->airspeedMeasurementSigma = _parameters.eas_noise;
+ }
return OK;
}
@@ -392,13 +506,14 @@ FixedwingEstimator::task_main_trampoline(int argc, char *argv[])
estimator::g_estimator->task_main();
}
-float dt = 0.0f; // time lapsed since last covariance prediction
-
void
FixedwingEstimator::task_main()
{
+ _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
_ekf = new AttPosEKF();
+ float dt = 0.0f; // time lapsed since last covariance prediction
+ _filter_start_time = hrt_absolute_time();
if (!_ekf) {
errx(1, "failed allocating EKF filter - out of RAM!");
@@ -412,6 +527,7 @@ FixedwingEstimator::task_main()
_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
_vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
+ _home_sub = orb_subscribe(ORB_ID(home_position));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vstatus_sub, 200);
@@ -431,26 +547,11 @@ FixedwingEstimator::task_main()
orb_set_interval(_sensor_combined_sub, 4);
#endif
+ /* sets also parameters in the EKF object */
parameters_update();
- /* set initial filter state */
- _ekf->fuseVelData = false;
- _ekf->fusePosData = false;
- _ekf->fuseHgtData = false;
- _ekf->fuseMagData = false;
- _ekf->fuseVtasData = false;
- _ekf->statesInitialised = false;
-
- /* initialize measurement data */
- _ekf->VtasMeas = 0.0f;
Vector3f lastAngRate = {0.0f, 0.0f, 0.0f};
- Vector3f lastAccel = {0.0f, 0.0f, -9.81f};
- _ekf->dVelIMU.x = 0.0f;
- _ekf->dVelIMU.y = 0.0f;
- _ekf->dVelIMU.z = 0.0f;
- _ekf->dAngIMU.x = 0.0f;
- _ekf->dAngIMU.y = 0.0f;
- _ekf->dAngIMU.z = 0.0f;
+ Vector3f lastAccel = {0.0f, 0.0f, 0.0f};
/* wakeup source(s) */
struct pollfd fds[2];
@@ -466,9 +567,8 @@ FixedwingEstimator::task_main()
fds[1].events = POLLIN;
#endif
- hrt_abstime start_time = hrt_absolute_time();
-
bool newDataGps = false;
+ bool newHgtData = false;
bool newAdsData = false;
bool newDataMag = false;
@@ -503,19 +603,52 @@ FixedwingEstimator::task_main()
if (fds[1].revents & POLLIN) {
/* check vehicle status for changes to publication state */
+ bool prev_hil = (_vstatus.hil_state == HIL_STATE_ON);
vehicle_status_poll();
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 */
+ if (!prev_hil && (_vstatus.hil_state == HIL_STATE_ON)) {
+ /* system is in HIL now, wait for measurements to come in one last round */
+ usleep(60000);
+
+#ifndef SENSOR_COMBINED_SUB
+ orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro);
+ orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel);
+ orb_copy(ORB_ID(sensor_mag), _mag_sub, &_mag);
+#else
+ /* now read all sensor publications to ensure all real sensor data is purged */
+ orb_copy(ORB_ID(sensor_combined), _sensor_combined_sub, &_sensor_combined);
+#endif
+
+ /* 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;
+ _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;
+ }
+
/**
* PART ONE: COLLECT ALL DATA
**/
- hrt_abstime last_sensor_timestamp;
-
/* load local copies */
#ifndef SENSOR_COMBINED_SUB
orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &_gyro);
@@ -529,27 +662,46 @@ FixedwingEstimator::task_main()
}
last_sensor_timestamp = _gyro.timestamp;
- _ekf.IMUmsec = _gyro.timestamp / 1e3f;
+ IMUmsec = _gyro.timestamp / 1e3f;
float deltaT = (_gyro.timestamp - last_run) / 1e6f;
last_run = _gyro.timestamp;
/* guard against too large deltaT's */
- if (deltaT > 1.0f)
+ if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
deltaT = 0.01f;
+ }
// Always store data, independent of init status
/* fill in last data set */
_ekf->dtIMU = deltaT;
- _ekf->angRate.x = _gyro.x;
- _ekf->angRate.y = _gyro.y;
- _ekf->angRate.z = _gyro.z;
+ if (isfinite(_gyro.x) &&
+ isfinite(_gyro.y) &&
+ isfinite(_gyro.z)) {
+ _ekf->angRate.x = _gyro.x;
+ _ekf->angRate.y = _gyro.y;
+ _ekf->angRate.z = _gyro.z;
+
+ if (!_gyro_valid) {
+ lastAngRate = _ekf->angRate;
+ }
+
+ _gyro_valid = true;
+ }
- _ekf->accel.x = _accel.x;
- _ekf->accel.y = _accel.y;
- _ekf->accel.z = _accel.z;
+ if (accel_updated) {
+ _ekf->accel.x = _accel.x;
+ _ekf->accel.y = _accel.y;
+ _ekf->accel.z = _accel.z;
+
+ if (!_accel_valid) {
+ lastAccel = _ekf->accel;
+ }
+
+ _accel_valid = true;
+ }
_ekf->dAngIMU = 0.5f * (angRate + lastAngRate) * dtIMU;
_ekf->lastAngRate = angRate;
@@ -565,6 +717,8 @@ FixedwingEstimator::task_main()
if (last_accel != _sensor_combined.accelerometer_timestamp) {
accel_updated = true;
+ } else {
+ accel_updated = false;
}
last_accel = _sensor_combined.accelerometer_timestamp;
@@ -575,23 +729,43 @@ FixedwingEstimator::task_main()
IMUmsec = _sensor_combined.timestamp / 1e3f;
float deltaT = (_sensor_combined.timestamp - last_run) / 1e6f;
- last_run = _sensor_combined.timestamp;
/* guard against too large deltaT's */
- if (deltaT > 1.0f || deltaT < 0.000001f)
+ if (!isfinite(deltaT) || deltaT > 1.0f || deltaT < 0.000001f) {
deltaT = 0.01f;
+ }
+
+ last_run = _sensor_combined.timestamp;
// Always store data, independent of init status
/* fill in last data set */
_ekf->dtIMU = deltaT;
- _ekf->angRate.x = _sensor_combined.gyro_rad_s[0];
- _ekf->angRate.y = _sensor_combined.gyro_rad_s[1];
- _ekf->angRate.z = _sensor_combined.gyro_rad_s[2];
+ if (isfinite(_sensor_combined.gyro_rad_s[0]) &&
+ isfinite(_sensor_combined.gyro_rad_s[1]) &&
+ isfinite(_sensor_combined.gyro_rad_s[2])) {
+ _ekf->angRate.x = _sensor_combined.gyro_rad_s[0];
+ _ekf->angRate.y = _sensor_combined.gyro_rad_s[1];
+ _ekf->angRate.z = _sensor_combined.gyro_rad_s[2];
+
+ if (!_gyro_valid) {
+ lastAngRate = _ekf->angRate;
+ }
+
+ _gyro_valid = true;
+ }
+
+ if (accel_updated) {
+ _ekf->accel.x = _sensor_combined.accelerometer_m_s2[0];
+ _ekf->accel.y = _sensor_combined.accelerometer_m_s2[1];
+ _ekf->accel.z = _sensor_combined.accelerometer_m_s2[2];
+
+ if (!_accel_valid) {
+ lastAccel = _ekf->accel;
+ }
- _ekf->accel.x = _sensor_combined.accelerometer_m_s2[0];
- _ekf->accel.y = _sensor_combined.accelerometer_m_s2[1];
- _ekf->accel.z = _sensor_combined.accelerometer_m_s2[2];
+ _accel_valid = true;
+ }
_ekf->dAngIMU = 0.5f * (_ekf->angRate + lastAngRate) * _ekf->dtIMU;
lastAngRate = _ekf->angRate;
@@ -635,11 +809,13 @@ FixedwingEstimator::task_main()
perf_count(_perf_gps);
if (_gps.fix_type < 3) {
- gps_updated = false;
newDataGps = false;
} else {
+ /* store time of valid GPS measurement */
+ _gps_start_time = hrt_absolute_time();
+
/* check if we had a GPS outage for a long time */
if (hrt_elapsed_time(&last_gps) > 5 * 1000 * 1000) {
_ekf->ResetPosition();
@@ -660,6 +836,21 @@ FixedwingEstimator::task_main()
_ekf->gpsLat = math::radians(_gps.lat / (double)1e7);
_ekf->gpsLon = math::radians(_gps.lon / (double)1e7) - M_PI;
_ekf->gpsHgt = _gps.alt / 1e3f;
+
+ // if (_gps.s_variance_m_s > 0.25f && _gps.s_variance_m_s < 100.0f * 100.0f) {
+ // _ekf->vneSigma = sqrtf(_gps.s_variance_m_s);
+ // } else {
+ // _ekf->vneSigma = _parameters.velne_noise;
+ // }
+
+ // if (_gps.p_variance_m > 0.25f && _gps.p_variance_m < 100.0f * 100.0f) {
+ // _ekf->posNeSigma = sqrtf(_gps.p_variance_m);
+ // } else {
+ // _ekf->posNeSigma = _parameters.posne_noise;
+ // }
+
+ // warnx("vel: %8.4f pos: %8.4f", _gps.s_variance_m_s, _gps.p_variance_m);
+
newDataGps = true;
}
@@ -672,10 +863,17 @@ FixedwingEstimator::task_main()
if (baro_updated) {
orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
- _ekf->baroHgt = _baro.altitude - _baro_ref;
+ _ekf->baroHgt = _baro.altitude;
- // Could use a blend of GPS and baro alt data if desired
- _ekf->hgtMea = 1.0f * _ekf->baroHgt + 0.0f * _ekf->gpsHgt;
+ if (!_baro_init) {
+ _baro_ref = _baro.altitude;
+ _baro_init = true;
+ warnx("ALT REF INIT");
+ }
+
+ newHgtData = true;
+ } else {
+ newHgtData = false;
}
#ifndef SENSOR_COMBINED_SUB
@@ -684,6 +882,8 @@ FixedwingEstimator::task_main()
if (mag_updated) {
+ _mag_valid = true;
+
perf_count(_perf_mag);
#ifndef SENSOR_COMBINED_SUB
@@ -727,6 +927,8 @@ FixedwingEstimator::task_main()
*/
int check = _ekf->CheckAndBound();
+ const char* ekfname = "[ekf] ";
+
switch (check) {
case 0:
/* all ok */
@@ -735,26 +937,38 @@ FixedwingEstimator::task_main()
{
const char* str = "NaN in states, resetting";
warnx("%s", str);
- mavlink_log_critical(_mavlink_fd, 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, str);
+ mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str);
break;
}
case 3:
{
- const char* str = "switching dynamic / static state";
+ const char* str = "switching to dynamic state";
warnx("%s", str);
- mavlink_log_critical(_mavlink_fd, 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);
+ }
}
- // If non-zero, we got a problem
+ // 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;
@@ -770,7 +984,7 @@ FixedwingEstimator::task_main()
rep.kalman_gain_nan = ekf_report.kalmanGainsNaN;
// Copy all states or at least all that we can fit
- int i = 0;
+ 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;
@@ -786,6 +1000,23 @@ FixedwingEstimator::task_main()
} 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
+ continue;
+
}
@@ -793,52 +1024,70 @@ FixedwingEstimator::task_main()
* PART TWO: EXECUTE THE FILTER
**/
- // Wait long enough to ensure all sensors updated once
- // XXX we rather want to check all updated
+ if ((hrt_elapsed_time(&_filter_start_time) > FILTER_INIT_DELAY) && _baro_init && _gyro_valid && _accel_valid && _mag_valid) {
+ float initVelNED[3];
- if (hrt_elapsed_time(&start_time) > 100000) {
+ if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph_m < _parameters.pos_stddev_threshold && _gps.epv_m < _parameters.pos_stddev_threshold) {
- if (!_gps_initialized && (_ekf->GPSstatus == 3)) {
- _ekf->velNED[0] = _gps.vel_n_m_s;
- _ekf->velNED[1] = _gps.vel_e_m_s;
- _ekf->velNED[2] = _gps.vel_d_m_s;
+ initVelNED[0] = _gps.vel_n_m_s;
+ initVelNED[1] = _gps.vel_e_m_s;
+ initVelNED[2] = _gps.vel_d_m_s;
- double lat = _gps.lat * 1e-7;
- double lon = _gps.lon * 1e-7;
- float alt = _gps.alt * 1e-3;
+ // GPS is in scaled integers, convert
+ double lat = _gps.lat / 1.0e7;
+ double lon = _gps.lon / 1.0e7;
+ float gps_alt = _gps.alt / 1e3f;
- _ekf->InitialiseFilter(_ekf->velNED);
+ // Set up height correctly
+ orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
+ _baro_gps_offset = _baro_ref - _baro.altitude;
+ _ekf->baroHgt = _baro.altitude;
+ _ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref));
+
+ // Set up position variables correctly
+ _ekf->GPSstatus = _gps.fix_type;
+
+ _ekf->gpsLat = math::radians(lat);
+ _ekf->gpsLon = math::radians(lon) - M_PI;
+ _ekf->gpsHgt = gps_alt;
+
+ // Look up mag declination based on current position
+ float declination = math::radians(get_mag_declination(lat, lon));
+
+ _ekf->InitialiseFilter(initVelNED, math::radians(lat), math::radians(lon) - M_PI, gps_alt, declination);
// Initialize projection
- _local_pos.ref_lat = _gps.lat;
- _local_pos.ref_lon = _gps.lon;
- _local_pos.ref_alt = alt;
+ _local_pos.ref_lat = lat;
+ _local_pos.ref_lon = lon;
+ _local_pos.ref_alt = gps_alt;
_local_pos.ref_timestamp = _gps.timestamp_position;
- // Store
- orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro);
- _baro_ref = _baro.altitude;
- _ekf->baroHgt = _baro.altitude - _baro_ref;
- _baro_gps_offset = _baro_ref - _local_pos.ref_alt;
-
- // XXX this is not multithreading safe
map_projection_init(&_pos_ref, lat, lon);
- mavlink_log_info(_mavlink_fd, "[position estimator] init ref: lat=%.7f, lon=%.7f, alt=%.2f", lat, lon, alt);
+ mavlink_log_info(_mavlink_fd, "[ekf] ref: LA %.4f,LO %.4f,ALT %.2f", lat, lon, (double)gps_alt);
+ warnx("HOME/REF: LA %8.4f,LO %8.4f,ALT %8.2f V: %8.4f %8.4f %8.4f", lat, lon, (double)gps_alt,
+ (double)_ekf->velNED[0], (double)_ekf->velNED[1], (double)_ekf->velNED[2]);
+ warnx("BARO: %8.4f m / ref: %8.4f m / 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));
_gps_initialized = true;
} else if (!_ekf->statesInitialised) {
- _ekf->velNED[0] = 0.0f;
- _ekf->velNED[1] = 0.0f;
- _ekf->velNED[2] = 0.0f;
+
+ 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->InitialiseFilter(_ekf->velNED);
+
+ _local_pos.ref_alt = _baro_ref;
+ _baro_gps_offset = 0.0f;
+
+ _ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f);
}
}
@@ -872,10 +1121,10 @@ FixedwingEstimator::task_main()
// perform a covariance prediction if the total delta angle has exceeded the limit
// or the time limit will be exceeded at the next IMU update
- if ((dt >= (covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > covDelAngMax)) {
+ if ((dt >= (_ekf->covTimeStepMax - _ekf->dtIMU)) || (_ekf->summedDelAng.length() > _ekf->covDelAngMax)) {
_ekf->CovariancePrediction(dt);
- _ekf->summedDelAng = _ekf->summedDelAng.zero();
- _ekf->summedDelVel = _ekf->summedDelVel.zero();
+ _ekf->summedDelAng.zero();
+ _ekf->summedDelVel.zero();
dt = 0.0f;
}
@@ -926,9 +1175,9 @@ FixedwingEstimator::task_main()
_ekf->fusePosData = false;
}
- if (newAdsData && _ekf->statesInitialised) {
+ if (newHgtData && _ekf->statesInitialised) {
// Could use a blend of GPS and baro alt data if desired
- _ekf->hgtMea = 1.0f * _ekf->baroHgt + 0.0f * _ekf->gpsHgt;
+ _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));
@@ -1017,7 +1266,8 @@ FixedwingEstimator::task_main()
_local_pos.timestamp = last_sensor_timestamp;
_local_pos.x = _ekf->states[7];
_local_pos.y = _ekf->states[8];
- _local_pos.z = _ekf->states[9];
+ // XXX need to announce change of Z reference somehow elegantly
+ _local_pos.z = _ekf->states[9] - _baro_gps_offset;
_local_pos.vx = _ekf->states[4];
_local_pos.vy = _ekf->states[5];
@@ -1050,6 +1300,8 @@ FixedwingEstimator::task_main()
_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;
}
if (_local_pos.v_xy_valid) {
@@ -1060,8 +1312,8 @@ FixedwingEstimator::task_main()
_global_pos.vel_e = 0.0f;
}
- /* local pos alt is negative, change sign and add alt offset */
- _global_pos.alt = _local_pos.ref_alt + (-_local_pos.z);
+ /* local pos alt is negative, change sign and add alt offsets */
+ _global_pos.alt = _local_pos.ref_alt + _baro_gps_offset + (-_local_pos.z);
if (_local_pos.v_z_valid) {
_global_pos.vel_d = _local_pos.vz;
@@ -1102,7 +1354,7 @@ FixedwingEstimator::start()
ASSERT(_estimator_task == -1);
/* start the task */
- _estimator_task = task_spawn_cmd("fw_att_pos_estimator",
+ _estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
6000,
@@ -1136,7 +1388,8 @@ FixedwingEstimator::print_status()
// 15-17: Earth Magnetic Field Vector - gauss (North, East, Down)
// 18-20: Body Magnetic Field Vector - gauss (X,Y,Z)
- printf("dtIMU: %8.6f dt: %8.6f IMUmsec: %d\n", _ekf->dtIMU, dt, (int)IMUmsec);
+ printf("dtIMU: %8.6f IMUmsec: %d\n", (double)_ekf->dtIMU, (int)IMUmsec);
+ printf("ref alt: %8.6f\n", (double)_local_pos.ref_alt);
printf("dvel: %8.6f %8.6f %8.6f accel: %8.6f %8.6f %8.6f\n", (double)_ekf->dVelIMU.x, (double)_ekf->dVelIMU.y, (double)_ekf->dVelIMU.z, (double)_ekf->accel.x, (double)_ekf->accel.y, (double)_ekf->accel.z);
printf("dang: %8.4f %8.4f %8.4f dang corr: %8.4f %8.4f %8.4f\n" , (double)_ekf->dAngIMU.x, (double)_ekf->dAngIMU.y, (double)_ekf->dAngIMU.z, (double)_ekf->correctedDelAng.x, (double)_ekf->correctedDelAng.y, (double)_ekf->correctedDelAng.z);
printf("states (quat) [1-4]: %8.4f, %8.4f, %8.4f, %8.4f\n", (double)_ekf->states[0], (double)_ekf->states[1], (double)_ekf->states[2], (double)_ekf->states[3]);
@@ -1180,13 +1433,13 @@ int FixedwingEstimator::trip_nan() {
_ekf->states[5] = nan_val;
usleep(100000);
- // warnx("tripping covariance #1 with NaN values");
- // KH[2][2] = nan_val; // intermediate result used for covariance updates
- // usleep(100000);
+ warnx("tripping covariance #1 with NaN values");
+ _ekf->KH[2][2] = nan_val; // intermediate result used for covariance updates
+ usleep(100000);
- // warnx("tripping covariance #2 with NaN values");
- // KHP[5][5] = nan_val; // intermediate result used for covariance updates
- // usleep(100000);
+ warnx("tripping covariance #2 with NaN values");
+ _ekf->KHP[5][5] = nan_val; // intermediate result used for covariance updates
+ usleep(100000);
warnx("tripping covariance #3 with NaN values");
_ekf->P[3][3] = nan_val; // covariance matrix
@@ -1208,10 +1461,10 @@ int FixedwingEstimator::trip_nan() {
return ret;
}
-int fw_att_pos_estimator_main(int argc, char *argv[])
+int ekf_att_pos_estimator_main(int argc, char *argv[])
{
if (argc < 1)
- errx(1, "usage: fw_att_pos_estimator {start|stop|status}");
+ errx(1, "usage: ekf_att_pos_estimator {start|stop|status}");
if (!strcmp(argv[1], "start")) {
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
new file mode 100644
index 000000000..8c82dd6c1
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_params.c
@@ -0,0 +1,271 @@
+/****************************************************************************
+ *
+ * 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 ekf_att_pos_estimator_params.c
+ *
+ * Parameters defined by the attitude and position estimator task
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <nuttx/config.h>
+
+#include <systemlib/param/param.h>
+
+/*
+ * Estimator parameters, accessible via MAVLink
+ *
+ */
+
+/**
+ * Velocity estimate delay
+ *
+ * The delay in milliseconds of the velocity estimate from GPS.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_VEL_DELAY_MS, 230);
+
+/**
+ * Position estimate delay
+ *
+ * The delay in milliseconds of the position estimate from GPS.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_POS_DELAY_MS, 210);
+
+/**
+ * Height estimate delay
+ *
+ * The delay in milliseconds of the height estimate from the barometer.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_HGT_DELAY_MS, 350);
+
+/**
+ * Mag estimate delay
+ *
+ * The delay in milliseconds of the magnetic field estimate from
+ * the magnetometer.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_MAG_DELAY_MS, 30);
+
+/**
+ * True airspeeed estimate delay
+ *
+ * The delay in milliseconds of the airspeed estimate.
+ *
+ * @min 0
+ * @max 1000
+ * @group Position Estimator
+ */
+PARAM_DEFINE_INT32(PE_TAS_DELAY_MS, 210);
+
+/**
+ * GPS vs. barometric altitude update weight
+ *
+ * RE-CHECK this.
+ *
+ * @min 0.0
+ * @max 1.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_GPS_ALT_WGT, 0.9f);
+
+/**
+ * Airspeed measurement noise.
+ *
+ * Increasing this value will make the filter trust this sensor
+ * less and trust other sensors more.
+ *
+ * @min 0.5
+ * @max 5.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_EAS_NOISE, 1.4f);
+
+/**
+ * Velocity measurement noise in north-east (horizontal) direction.
+ *
+ * Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5
+ *
+ * @min 0.05
+ * @max 5.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_VELNE_NOISE, 0.3f);
+
+/**
+ * Velocity noise in down (vertical) direction
+ *
+ * Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7
+ *
+ * @min 0.05
+ * @max 5.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_VELD_NOISE, 0.5f);
+
+/**
+ * Position noise in north-east (horizontal) direction
+ *
+ * Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5
+ *
+ * @min 0.1
+ * @max 10.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_POSNE_NOISE, 0.5f);
+
+/**
+ * Position noise in down (vertical) direction
+ *
+ * Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0
+ *
+ * @min 0.1
+ * @max 10.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_POSD_NOISE, 0.5f);
+
+/**
+ * Magnetometer measurement noise
+ *
+ * Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05
+ *
+ * @min 0.1
+ * @max 10.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_MAG_NOISE, 0.05f);
+
+/**
+ * Gyro process noise
+ *
+ * Generic defaults: 0.015, multicopters: 0.015, ground vehicles: 0.015.
+ * This noise controls how much the filter trusts the gyro measurements.
+ * Increasing it makes the filter trust the gyro less and other sensors more.
+ *
+ * @min 0.001
+ * @max 0.05
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_GYRO_PNOISE, 0.015f);
+
+/**
+ * Accelerometer process noise
+ *
+ * Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25.
+ * Increasing this value makes the filter trust the accelerometer less
+ * and other sensors more.
+ *
+ * @min 0.05
+ * @max 1.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_ACC_PNOISE, 0.25f);
+
+/**
+ * Gyro bias estimate process noise
+ *
+ * Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f.
+ * Increasing this value will make the gyro bias converge faster but noisier.
+ *
+ * @min 0.0000001
+ * @max 0.00001
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_GBIAS_PNOISE, 1e-07f);
+
+/**
+ * Accelerometer bias estimate process noise
+ *
+ * Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f.
+ * Increasing this value makes the bias estimation faster and noisier.
+ *
+ * @min 0.00001
+ * @max 0.001
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_ABIAS_PNOISE, 0.00005f);
+
+/**
+ * Magnetometer earth frame offsets process noise
+ *
+ * Generic defaults: 0.0001, multicopters: 0.0001, ground vehicles: 0.0001.
+ * Increasing this value makes the magnetometer earth bias estimate converge
+ * faster but also noisier.
+ *
+ * @min 0.0001
+ * @max 0.01
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_MAGE_PNOISE, 0.0003f);
+
+/**
+ * Magnetometer body frame offsets process noise
+ *
+ * Generic defaults: 0.0003, multicopters: 0.0003, ground vehicles: 0.0003.
+ * Increasing this value makes the magnetometer body bias estimate converge faster
+ * but also noisier.
+ *
+ * @min 0.0001
+ * @max 0.01
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_MAGB_PNOISE, 0.0003f);
+
+/**
+ * Threshold for filter initialization.
+ *
+ * If the standard deviation of the GPS position estimate is below this threshold
+ * in meters, the filter will initialize.
+ *
+ * @min 0.3
+ * @max 10.0
+ * @group Position Estimator
+ */
+PARAM_DEFINE_FLOAT(PE_POSDEV_INIT, 5.0f);
diff --git a/src/modules/ekf_att_pos_estimator/estimator.cpp b/src/modules/ekf_att_pos_estimator/estimator.cpp
new file mode 100644
index 000000000..5db1adbb3
--- /dev/null
+++ b/src/modules/ekf_att_pos_estimator/estimator.cpp
@@ -0,0 +1,2609 @@
+#include "estimator.h"
+#include <string.h>
+#include <stdarg.h>
+
+// Define EKF_DEBUG here to enable the debug print calls
+// if the macro is not set, these will be completely
+// optimized out by the compiler.
+//#define EKF_DEBUG
+
+#ifdef EKF_DEBUG
+#include <stdio.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.
+ */
+{
+
+ ZeroVariables();
+ 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;
+ float rotationMag;
+ float qUpdated[4];
+ float quatMag;
+ float deltaQuat[4];
+ const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS};
+
+// Remove sensor bias errors
+ correctedDelAng.x = dAngIMU.x - states[10];
+ correctedDelAng.y = dAngIMU.y - states[11];
+ correctedDelAng.z = dAngIMU.z - states[12];
+ dVelIMU.x = dVelIMU.x;
+ dVelIMU.y = dVelIMU.y;
+ dVelIMU.z = dVelIMU.z - states[13];
+
+// 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] = cosf(0.5f*rotationMag);
+ float rotScaler = (sinf(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;
+ float dvz_b;
+
+ // arrays
+ float processNoise[n_states];
+ float SF[15];
+ float SG[8];
+ float SQ[11];
+ float SPP[8] = {0};
+ 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=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;
+
+ // square all sigmas
+ for (unsigned i = 0; i < n_states; 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];
+ dvz_b = states[13];
+ gyroProcessNoise = ConstrainFloat(gyroProcessNoise, 1e-3f, 5e-2f);
+ daxCov = sq(dt*gyroProcessNoise);
+ dayCov = sq(dt*gyroProcessNoise);
+ dazCov = sq(dt*gyroProcessNoise);
+ if (onGround) dazCov = dazCov * sq(yawVarScale);
+ accelProcessNoise = ConstrainFloat(accelProcessNoise, 5e-2, 1.0f);
+ dvxCov = sq(dt*accelProcessNoise);
+ dvyCov = sq(dt*accelProcessNoise);
+ dvzCov = sq(dt*accelProcessNoise);
+
+ // Predicted covariance calculation
+ SF[0] = dvz - dvz_b;
+ SF[1] = 2*q3*SF[0] + 2*dvx*q1 + 2*dvy*q2;
+ SF[2] = 2*dvx*q3 - 2*q1*SF[0] + 2*dvy*q0;
+ SF[3] = 2*q2*SF[0] + 2*dvx*q0 - 2*dvy*q3;
+ SF[4] = day/2 - day_b/2;
+ SF[5] = daz/2 - daz_b/2;
+ SF[6] = dax/2 - dax_b/2;
+ SF[7] = dax_b/2 - dax/2;
+ SF[8] = daz_b/2 - daz/2;
+ SF[9] = day_b/2 - day/2;
+ SF[10] = 2*q0*SF[0];
+ SF[11] = q1/2;
+ SF[12] = q2/2;
+ SF[13] = q3/2;
+ SF[14] = 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[10] + SF[14] - 2*dvx*q2;
+ SPP[1] = 2*q2*SF[0] + 2*dvx*q0 - 2*dvy*q3;
+ SPP[2] = 2*dvx*q3 - 2*q1*SF[0] + 2*dvy*q0;
+ SPP[3] = 2*q0*q1 - 2*q2*q3;
+ SPP[4] = 2*q0*q2 + 2*q1*q3;
+ SPP[5] = sq(q0) - sq(q1) - sq(q2) + sq(q3);
+ SPP[6] = SF[13];
+ SPP[7] = SF[12];
+
+ nextP[0][0] = P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6] + (daxCov*SQ[10])/4 + SF[7]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SF[9]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) + SF[8]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) + SF[11]*(P[0][10] + P[1][10]*SF[7] + P[2][10]*SF[9] + P[3][10]*SF[8] + P[10][10]*SF[11] + P[11][10]*SPP[7] + P[12][10]*SPP[6]) + SPP[7]*(P[0][11] + P[1][11]*SF[7] + P[2][11]*SF[9] + P[3][11]*SF[8] + P[10][11]*SF[11] + P[11][11]*SPP[7] + P[12][11]*SPP[6]) + SPP[6]*(P[0][12] + P[1][12]*SF[7] + P[2][12]*SF[9] + P[3][12]*SF[8] + P[10][12]*SF[11] + P[11][12]*SPP[7] + P[12][12]*SPP[6]) + (dayCov*sq(q2))/4 + (dazCov*sq(q3))/4;
+ nextP[0][1] = P[0][1] + SQ[8] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6] + SF[6]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) + SF[5]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) + SF[9]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) + SPP[6]*(P[0][11] + P[1][11]*SF[7] + P[2][11]*SF[9] + P[3][11]*SF[8] + P[10][11]*SF[11] + P[11][11]*SPP[7] + P[12][11]*SPP[6]) - SPP[7]*(P[0][12] + P[1][12]*SF[7] + P[2][12]*SF[9] + P[3][12]*SF[8] + P[10][12]*SF[11] + P[11][12]*SPP[7] + P[12][12]*SPP[6]) - (q0*(P[0][10] + P[1][10]*SF[7] + P[2][10]*SF[9] + P[3][10]*SF[8] + P[10][10]*SF[11] + P[11][10]*SPP[7] + P[12][10]*SPP[6]))/2;
+ nextP[0][2] = P[0][2] + SQ[7] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6] + SF[4]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) + SF[8]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SF[6]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) + SF[11]*(P[0][12] + P[1][12]*SF[7] + P[2][12]*SF[9] + P[3][12]*SF[8] + P[10][12]*SF[11] + P[11][12]*SPP[7] + P[12][12]*SPP[6]) - SPP[6]*(P[0][10] + P[1][10]*SF[7] + P[2][10]*SF[9] + P[3][10]*SF[8] + P[10][10]*SF[11] + P[11][10]*SPP[7] + P[12][10]*SPP[6]) - (q0*(P[0][11] + P[1][11]*SF[7] + P[2][11]*SF[9] + P[3][11]*SF[8] + P[10][11]*SF[11] + P[11][11]*SPP[7] + P[12][11]*SPP[6]))/2;
+ nextP[0][3] = P[0][3] + SQ[6] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6] + SF[5]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) + SF[4]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SF[7]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) - SF[11]*(P[0][11] + P[1][11]*SF[7] + P[2][11]*SF[9] + P[3][11]*SF[8] + P[10][11]*SF[11] + P[11][11]*SPP[7] + P[12][11]*SPP[6]) + SPP[7]*(P[0][10] + P[1][10]*SF[7] + P[2][10]*SF[9] + P[3][10]*SF[8] + P[10][10]*SF[11] + P[11][10]*SPP[7] + P[12][10]*SPP[6]) - (q0*(P[0][12] + P[1][12]*SF[7] + P[2][12]*SF[9] + P[3][12]*SF[8] + P[10][12]*SF[11] + P[11][12]*SPP[7] + P[12][12]*SPP[6]))/2;
+ nextP[0][4] = P[0][4] + P[1][4]*SF[7] + P[2][4]*SF[9] + P[3][4]*SF[8] + P[10][4]*SF[11] + P[11][4]*SPP[7] + P[12][4]*SPP[6] + SF[3]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) + SF[1]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SPP[0]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) - SPP[2]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) - SPP[4]*(P[0][13] + P[1][13]*SF[7] + P[2][13]*SF[9] + P[3][13]*SF[8] + P[10][13]*SF[11] + P[11][13]*SPP[7] + P[12][13]*SPP[6]);
+ nextP[0][5] = P[0][5] + P[1][5]*SF[7] + P[2][5]*SF[9] + P[3][5]*SF[8] + P[10][5]*SF[11] + P[11][5]*SPP[7] + P[12][5]*SPP[6] + SF[2]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) + SF[1]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) + SF[3]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) - SPP[0]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SPP[3]*(P[0][13] + P[1][13]*SF[7] + P[2][13]*SF[9] + P[3][13]*SF[8] + P[10][13]*SF[11] + P[11][13]*SPP[7] + P[12][13]*SPP[6]);
+ nextP[0][6] = P[0][6] + P[1][6]*SF[7] + P[2][6]*SF[9] + P[3][6]*SF[8] + P[10][6]*SF[11] + P[11][6]*SPP[7] + P[12][6]*SPP[6] + SF[2]*(P[0][1] + P[1][1]*SF[7] + P[2][1]*SF[9] + P[3][1]*SF[8] + P[10][1]*SF[11] + P[11][1]*SPP[7] + P[12][1]*SPP[6]) + SF[1]*(P[0][3] + P[1][3]*SF[7] + P[2][3]*SF[9] + P[3][3]*SF[8] + P[10][3]*SF[11] + P[11][3]*SPP[7] + P[12][3]*SPP[6]) + SPP[0]*(P[0][0] + P[1][0]*SF[7] + P[2][0]*SF[9] + P[3][0]*SF[8] + P[10][0]*SF[11] + P[11][0]*SPP[7] + P[12][0]*SPP[6]) - SPP[1]*(P[0][2] + P[1][2]*SF[7] + P[2][2]*SF[9] + P[3][2]*SF[8] + P[10][2]*SF[11] + P[11][2]*SPP[7] + P[12][2]*SPP[6]) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[0][13] + P[1][13]*SF[7] + P[2][13]*SF[9] + P[3][13]*SF[8] + P[10][13]*SF[11] + P[11][13]*SPP[7] + P[12][13]*SPP[6]);
+ nextP[0][7] = P[0][7] + P[1][7]*SF[7] + P[2][7]*SF[9] + P[3][7]*SF[8] + P[10][7]*SF[11] + P[11][7]*SPP[7] + P[12][7]*SPP[6] + dt*(P[0][4] + P[1][4]*SF[7] + P[2][4]*SF[9] + P[3][4]*SF[8] + P[10][4]*SF[11] + P[11][4]*SPP[7] + P[12][4]*SPP[6]);
+ nextP[0][8] = P[0][8] + P[1][8]*SF[7] + P[2][8]*SF[9] + P[3][8]*SF[8] + P[10][8]*SF[11] + P[11][8]*SPP[7] + P[12][8]*SPP[6] + dt*(P[0][5] + P[1][5]*SF[7] + P[2][5]*SF[9] + P[3][5]*SF[8] + P[10][5]*SF[11] + P[11][5]*SPP[7] + P[12][5]*SPP[6]);
+ nextP[0][9] = P[0][9] + P[1][9]*SF[7] + P[2][9]*SF[9] + P[3][9]*SF[8] + P[10][9]*SF[11] + P[11][9]*SPP[7] + P[12][9]*SPP[6] + dt*(P[0][6] + P[1][6]*SF[7] + P[2][6]*SF[9] + P[3][6]*SF[8] + P[10][6]*SF[11] + P[11][6]*SPP[7] + P[12][6]*SPP[6]);
+ nextP[0][10] = P[0][10] + P[1][10]*SF[7] + P[2][10]*SF[9] + P[3][10]*SF[8] + P[10][10]*SF[11] + P[11][10]*SPP[7] + P[12][10]*SPP[6];
+ nextP[0][11] = P[0][11] + P[1][11]*SF[7] + P[2][11]*SF[9] + P[3][11]*SF[8] + P[10][11]*SF[11] + P[11][11]*SPP[7] + P[12][11]*SPP[6];
+ nextP[0][12] = P[0][12] + P[1][12]*SF[7] + P[2][12]*SF[9] + P[3][12]*SF[8] + P[10][12]*SF[11] + P[11][12]*SPP[7] + P[12][12]*SPP[6];
+ nextP[0][13] = P[0][13] + P[1][13]*SF[7] + P[2][13]*SF[9] + P[3][13]*SF[8] + P[10][13]*SF[11] + P[11][13]*SPP[7] + P[12][13]*SPP[6];
+ nextP[0][14] = P[0][14] + P[1][14]*SF[7] + P[2][14]*SF[9] + P[3][14]*SF[8] + P[10][14]*SF[11] + P[11][14]*SPP[7] + P[12][14]*SPP[6];
+ nextP[0][15] = P[0][15] + P[1][15]*SF[7] + P[2][15]*SF[9] + P[3][15]*SF[8] + P[10][15]*SF[11] + P[11][15]*SPP[7] + P[12][15]*SPP[6];
+ nextP[0][16] = P[0][16] + P[1][16]*SF[7] + P[2][16]*SF[9] + P[3][16]*SF[8] + P[10][16]*SF[11] + P[11][16]*SPP[7] + P[12][16]*SPP[6];
+ nextP[0][17] = P[0][17] + P[1][17]*SF[7] + P[2][17]*SF[9] + P[3][17]*SF[8] + P[10][17]*SF[11] + P[11][17]*SPP[7] + P[12][17]*SPP[6];
+ nextP[0][18] = P[0][18] + P[1][18]*SF[7] + P[2][18]*SF[9] + P[3][18]*SF[8] + P[10][18]*SF[11] + P[11][18]*SPP[7] + P[12][18]*SPP[6];
+ nextP[0][19] = P[0][19] + P[1][19]*SF[7] + P[2][19]*SF[9] + P[3][19]*SF[8] + P[10][19]*SF[11] + P[11][19]*SPP[7] + P[12][19]*SPP[6];
+ nextP[0][20] = P[0][20] + P[1][20]*SF[7] + P[2][20]*SF[9] + P[3][20]*SF[8] + P[10][20]*SF[11] + P[11][20]*SPP[7] + P[12][20]*SPP[6];
+ nextP[0][21] = P[0][21] + P[1][21]*SF[7] + P[2][21]*SF[9] + P[3][21]*SF[8] + P[10][21]*SF[11] + P[11][21]*SPP[7] + P[12][21]*SPP[6];
+ nextP[0][22] = P[0][22] + P[1][22]*SF[7] + P[2][22]*SF[9] + P[3][22]*SF[8] + P[10][22]*SF[11] + P[11][22]*SPP[7] + P[12][22]*SPP[6];
+ nextP[1][0] = P[1][0] + SQ[8] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2 + SF[7]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[9]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) + SF[8]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SF[11]*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2) + SPP[7]*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2) + SPP[6]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2);
+ nextP[1][1] = P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] + daxCov*SQ[9] - (P[10][1]*q0)/2 + SF[6]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[5]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) + SF[9]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SPP[6]*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2) - SPP[7]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2) + (dayCov*sq(q3))/4 + (dazCov*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2))/2;
+ nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[8]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[6]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SF[11]*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2) - SPP[6]*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2))/2;
+ nextP[1][3] = P[1][3] + SQ[4] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2 + SF[5]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[4]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[7]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) - SF[11]*(P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2) + SPP[7]*(P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2) - (q0*(P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2))/2;
+ nextP[1][4] = P[1][4] + P[0][4]*SF[6] + P[2][4]*SF[5] + P[3][4]*SF[9] + P[11][4]*SPP[6] - P[12][4]*SPP[7] - (P[10][4]*q0)/2 + SF[3]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[1]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SPP[0]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) - SPP[2]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) - SPP[4]*(P[1][13] + P[0][13]*SF[6] + P[2][13]*SF[5] + P[3][13]*SF[9] + P[11][13]*SPP[6] - P[12][13]*SPP[7] - (P[10][13]*q0)/2);
+ nextP[1][5] = P[1][5] + P[0][5]*SF[6] + P[2][5]*SF[5] + P[3][5]*SF[9] + P[11][5]*SPP[6] - P[12][5]*SPP[7] - (P[10][5]*q0)/2 + SF[2]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) + SF[1]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) + SF[3]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) - SPP[0]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SPP[3]*(P[1][13] + P[0][13]*SF[6] + P[2][13]*SF[5] + P[3][13]*SF[9] + P[11][13]*SPP[6] - P[12][13]*SPP[7] - (P[10][13]*q0)/2);
+ nextP[1][6] = P[1][6] + P[0][6]*SF[6] + P[2][6]*SF[5] + P[3][6]*SF[9] + P[11][6]*SPP[6] - P[12][6]*SPP[7] - (P[10][6]*q0)/2 + SF[2]*(P[1][1] + P[0][1]*SF[6] + P[2][1]*SF[5] + P[3][1]*SF[9] + P[11][1]*SPP[6] - P[12][1]*SPP[7] - (P[10][1]*q0)/2) + SF[1]*(P[1][3] + P[0][3]*SF[6] + P[2][3]*SF[5] + P[3][3]*SF[9] + P[11][3]*SPP[6] - P[12][3]*SPP[7] - (P[10][3]*q0)/2) + SPP[0]*(P[1][0] + P[0][0]*SF[6] + P[2][0]*SF[5] + P[3][0]*SF[9] + P[11][0]*SPP[6] - P[12][0]*SPP[7] - (P[10][0]*q0)/2) - SPP[1]*(P[1][2] + P[0][2]*SF[6] + P[2][2]*SF[5] + P[3][2]*SF[9] + P[11][2]*SPP[6] - P[12][2]*SPP[7] - (P[10][2]*q0)/2) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[1][13] + P[0][13]*SF[6] + P[2][13]*SF[5] + P[3][13]*SF[9] + P[11][13]*SPP[6] - P[12][13]*SPP[7] - (P[10][13]*q0)/2);
+ nextP[1][7] = P[1][7] + P[0][7]*SF[6] + P[2][7]*SF[5] + P[3][7]*SF[9] + P[11][7]*SPP[6] - P[12][7]*SPP[7] - (P[10][7]*q0)/2 + dt*(P[1][4] + P[0][4]*SF[6] + P[2][4]*SF[5] + P[3][4]*SF[9] + P[11][4]*SPP[6] - P[12][4]*SPP[7] - (P[10][4]*q0)/2);
+ nextP[1][8] = P[1][8] + P[0][8]*SF[6] + P[2][8]*SF[5] + P[3][8]*SF[9] + P[11][8]*SPP[6] - P[12][8]*SPP[7] - (P[10][8]*q0)/2 + dt*(P[1][5] + P[0][5]*SF[6] + P[2][5]*SF[5] + P[3][5]*SF[9] + P[11][5]*SPP[6] - P[12][5]*SPP[7] - (P[10][5]*q0)/2);
+ nextP[1][9] = P[1][9] + P[0][9]*SF[6] + P[2][9]*SF[5] + P[3][9]*SF[9] + P[11][9]*SPP[6] - P[12][9]*SPP[7] - (P[10][9]*q0)/2 + dt*(P[1][6] + P[0][6]*SF[6] + P[2][6]*SF[5] + P[3][6]*SF[9] + P[11][6]*SPP[6] - P[12][6]*SPP[7] - (P[10][6]*q0)/2);
+ nextP[1][10] = P[1][10] + P[0][10]*SF[6] + P[2][10]*SF[5] + P[3][10]*SF[9] + P[11][10]*SPP[6] - P[12][10]*SPP[7] - (P[10][10]*q0)/2;
+ nextP[1][11] = P[1][11] + P[0][11]*SF[6] + P[2][11]*SF[5] + P[3][11]*SF[9] + P[11][11]*SPP[6] - P[12][11]*SPP[7] - (P[10][11]*q0)/2;
+ nextP[1][12] = P[1][12] + P[0][12]*SF[6] + P[2][12]*SF[5] + P[3][12]*SF[9] + P[11][12]*SPP[6] - P[12][12]*SPP[7] - (P[10][12]*q0)/2;
+ nextP[1][13] = P[1][13] + P[0][13]*SF[6] + P[2][13]*SF[5] + P[3][13]*SF[9] + P[11][13]*SPP[6] - P[12][13]*SPP[7] - (P[10][13]*q0)/2;
+ nextP[1][14] = P[1][14] + P[0][14]*SF[6] + P[2][14]*SF[5] + P[3][14]*SF[9] + P[11][14]*SPP[6] - P[12][14]*SPP[7] - (P[10][14]*q0)/2;
+ nextP[1][15] = P[1][15] + P[0][15]*SF[6] + P[2][15]*SF[5] + P[3][15]*SF[9] + P[11][15]*SPP[6] - P[12][15]*SPP[7] - (P[10][15]*q0)/2;
+ nextP[1][16] = P[1][16] + P[0][16]*SF[6] + P[2][16]*SF[5] + P[3][16]*SF[9] + P[11][16]*SPP[6] - P[12][16]*SPP[7] - (P[10][16]*q0)/2;
+ nextP[1][17] = P[1][17] + P[0][17]*SF[6] + P[2][17]*SF[5] + P[3][17]*SF[9] + P[11][17]*SPP[6] - P[12][17]*SPP[7] - (P[10][17]*q0)/2;
+ nextP[1][18] = P[1][18] + P[0][18]*SF[6] + P[2][18]*SF[5] + P[3][18]*SF[9] + P[11][18]*SPP[6] - P[12][18]*SPP[7] - (P[10][18]*q0)/2;
+ nextP[1][19] = P[1][19] + P[0][19]*SF[6] + P[2][19]*SF[5] + P[3][19]*SF[9] + P[11][19]*SPP[6] - P[12][19]*SPP[7] - (P[10][19]*q0)/2;
+ nextP[1][20] = P[1][20] + P[0][20]*SF[6] + P[2][20]*SF[5] + P[3][20]*SF[9] + P[11][20]*SPP[6] - P[12][20]*SPP[7] - (P[10][20]*q0)/2;
+ nextP[1][21] = P[1][21] + P[0][21]*SF[6] + P[2][21]*SF[5] + P[3][21]*SF[9] + P[11][21]*SPP[6] - P[12][21]*SPP[7] - (P[10][21]*q0)/2;
+ nextP[1][22] = P[1][22] + P[0][22]*SF[6] + P[2][22]*SF[5] + P[3][22]*SF[9] + P[11][22]*SPP[6] - P[12][22]*SPP[7] - (P[10][22]*q0)/2;
+ nextP[2][0] = P[2][0] + SQ[7] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2 + SF[7]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[9]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) + SF[8]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SF[11]*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2) + SPP[7]*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2) + SPP[6]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2);
+ nextP[2][1] = P[2][1] + SQ[5] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2 + SF[6]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[5]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) + SF[9]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SPP[6]*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2) - SPP[7]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2) - (q0*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2))/2;
+ nextP[2][2] = P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] + dayCov*SQ[9] + (dazCov*SQ[10])/4 - (P[11][2]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[8]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[6]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SF[11]*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2) - SPP[6]*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2) + (daxCov*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2))/2;
+ nextP[2][3] = P[2][3] + SQ[3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2 + SF[5]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[4]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[7]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) - SF[11]*(P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2) + SPP[7]*(P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2) - (q0*(P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2))/2;
+ nextP[2][4] = P[2][4] + P[0][4]*SF[4] + P[1][4]*SF[8] + P[3][4]*SF[6] + P[12][4]*SF[11] - P[10][4]*SPP[6] - (P[11][4]*q0)/2 + SF[3]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[1]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SPP[0]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) - SPP[2]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) - SPP[4]*(P[2][13] + P[0][13]*SF[4] + P[1][13]*SF[8] + P[3][13]*SF[6] + P[12][13]*SF[11] - P[10][13]*SPP[6] - (P[11][13]*q0)/2);
+ nextP[2][5] = P[2][5] + P[0][5]*SF[4] + P[1][5]*SF[8] + P[3][5]*SF[6] + P[12][5]*SF[11] - P[10][5]*SPP[6] - (P[11][5]*q0)/2 + SF[2]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) + SF[1]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) + SF[3]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) - SPP[0]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SPP[3]*(P[2][13] + P[0][13]*SF[4] + P[1][13]*SF[8] + P[3][13]*SF[6] + P[12][13]*SF[11] - P[10][13]*SPP[6] - (P[11][13]*q0)/2);
+ nextP[2][6] = P[2][6] + P[0][6]*SF[4] + P[1][6]*SF[8] + P[3][6]*SF[6] + P[12][6]*SF[11] - P[10][6]*SPP[6] - (P[11][6]*q0)/2 + SF[2]*(P[2][1] + P[0][1]*SF[4] + P[1][1]*SF[8] + P[3][1]*SF[6] + P[12][1]*SF[11] - P[10][1]*SPP[6] - (P[11][1]*q0)/2) + SF[1]*(P[2][3] + P[0][3]*SF[4] + P[1][3]*SF[8] + P[3][3]*SF[6] + P[12][3]*SF[11] - P[10][3]*SPP[6] - (P[11][3]*q0)/2) + SPP[0]*(P[2][0] + P[0][0]*SF[4] + P[1][0]*SF[8] + P[3][0]*SF[6] + P[12][0]*SF[11] - P[10][0]*SPP[6] - (P[11][0]*q0)/2) - SPP[1]*(P[2][2] + P[0][2]*SF[4] + P[1][2]*SF[8] + P[3][2]*SF[6] + P[12][2]*SF[11] - P[10][2]*SPP[6] - (P[11][2]*q0)/2) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[2][13] + P[0][13]*SF[4] + P[1][13]*SF[8] + P[3][13]*SF[6] + P[12][13]*SF[11] - P[10][13]*SPP[6] - (P[11][13]*q0)/2);
+ nextP[2][7] = P[2][7] + P[0][7]*SF[4] + P[1][7]*SF[8] + P[3][7]*SF[6] + P[12][7]*SF[11] - P[10][7]*SPP[6] - (P[11][7]*q0)/2 + dt*(P[2][4] + P[0][4]*SF[4] + P[1][4]*SF[8] + P[3][4]*SF[6] + P[12][4]*SF[11] - P[10][4]*SPP[6] - (P[11][4]*q0)/2);
+ nextP[2][8] = P[2][8] + P[0][8]*SF[4] + P[1][8]*SF[8] + P[3][8]*SF[6] + P[12][8]*SF[11] - P[10][8]*SPP[6] - (P[11][8]*q0)/2 + dt*(P[2][5] + P[0][5]*SF[4] + P[1][5]*SF[8] + P[3][5]*SF[6] + P[12][5]*SF[11] - P[10][5]*SPP[6] - (P[11][5]*q0)/2);
+ nextP[2][9] = P[2][9] + P[0][9]*SF[4] + P[1][9]*SF[8] + P[3][9]*SF[6] + P[12][9]*SF[11] - P[10][9]*SPP[6] - (P[11][9]*q0)/2 + dt*(P[2][6] + P[0][6]*SF[4] + P[1][6]*SF[8] + P[3][6]*SF[6] + P[12][6]*SF[11] - P[10][6]*SPP[6] - (P[11][6]*q0)/2);
+ nextP[2][10] = P[2][10] + P[0][10]*SF[4] + P[1][10]*SF[8] + P[3][10]*SF[6] + P[12][10]*SF[11] - P[10][10]*SPP[6] - (P[11][10]*q0)/2;
+ nextP[2][11] = P[2][11] + P[0][11]*SF[4] + P[1][11]*SF[8] + P[3][11]*SF[6] + P[12][11]*SF[11] - P[10][11]*SPP[6] - (P[11][11]*q0)/2;
+ nextP[2][12] = P[2][12] + P[0][12]*SF[4] + P[1][12]*SF[8] + P[3][12]*SF[6] + P[12][12]*SF[11] - P[10][12]*SPP[6] - (P[11][12]*q0)/2;
+ nextP[2][13] = P[2][13] + P[0][13]*SF[4] + P[1][13]*SF[8] + P[3][13]*SF[6] + P[12][13]*SF[11] - P[10][13]*SPP[6] - (P[11][13]*q0)/2;
+ nextP[2][14] = P[2][14] + P[0][14]*SF[4] + P[1][14]*SF[8] + P[3][14]*SF[6] + P[12][14]*SF[11] - P[10][14]*SPP[6] - (P[11][14]*q0)/2;
+ nextP[2][15] = P[2][15] + P[0][15]*SF[4] + P[1][15]*SF[8] + P[3][15]*SF[6] + P[12][15]*SF[11] - P[10][15]*SPP[6] - (P[11][15]*q0)/2;
+ nextP[2][16] = P[2][16] + P[0][16]*SF[4] + P[1][16]*SF[8] + P[3][16]*SF[6] + P[12][16]*SF[11] - P[10][16]*SPP[6] - (P[11][16]*q0)/2;
+ nextP[2][17] = P[2][17] + P[0][17]*SF[4] + P[1][17]*SF[8] + P[3][17]*SF[6] + P[12][17]*SF[11] - P[10][17]*SPP[6] - (P[11][17]*q0)/2;
+ nextP[2][18] = P[2][18] + P[0][18]*SF[4] + P[1][18]*SF[8] + P[3][18]*SF[6] + P[12][18]*SF[11] - P[10][18]*SPP[6] - (P[11][18]*q0)/2;
+ nextP[2][19] = P[2][19] + P[0][19]*SF[4] + P[1][19]*SF[8] + P[3][19]*SF[6] + P[12][19]*SF[11] - P[10][19]*SPP[6] - (P[11][19]*q0)/2;
+ nextP[2][20] = P[2][20] + P[0][20]*SF[4] + P[1][20]*SF[8] + P[3][20]*SF[6] + P[12][20]*SF[11] - P[10][20]*SPP[6] - (P[11][20]*q0)/2;
+ nextP[2][21] = P[2][21] + P[0][21]*SF[4] + P[1][21]*SF[8] + P[3][21]*SF[6] + P[12][21]*SF[11] - P[10][21]*SPP[6] - (P[11][21]*q0)/2;
+ nextP[2][22] = P[2][22] + P[0][22]*SF[4] + P[1][22]*SF[8] + P[3][22]*SF[6] + P[12][22]*SF[11] - P[10][22]*SPP[6] - (P[11][22]*q0)/2;
+ nextP[3][0] = P[3][0] + SQ[6] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2 + SF[7]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[9]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) + SF[8]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SF[11]*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2) + SPP[7]*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2) + SPP[6]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2);
+ nextP[3][1] = P[3][1] + SQ[4] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2 + SF[6]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[5]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) + SF[9]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SPP[6]*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2) - SPP[7]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2) - (q0*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2))/2;
+ nextP[3][2] = P[3][2] + SQ[3] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[8]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[6]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SF[11]*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2) - SPP[6]*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2) - (q0*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2))/2;
+ nextP[3][3] = P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] + (dayCov*SQ[10])/4 + dazCov*SQ[9] - (P[12][3]*q0)/2 + SF[5]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[4]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[7]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) - SF[11]*(P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2) + SPP[7]*(P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2) + (daxCov*sq(q2))/4 - (q0*(P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2))/2;
+ nextP[3][4] = P[3][4] + P[0][4]*SF[5] + P[1][4]*SF[4] + P[2][4]*SF[7] - P[11][4]*SF[11] + P[10][4]*SPP[7] - (P[12][4]*q0)/2 + SF[3]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[1]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SPP[0]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) - SPP[2]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) - SPP[4]*(P[3][13] + P[0][13]*SF[5] + P[1][13]*SF[4] + P[2][13]*SF[7] - P[11][13]*SF[11] + P[10][13]*SPP[7] - (P[12][13]*q0)/2);
+ nextP[3][5] = P[3][5] + P[0][5]*SF[5] + P[1][5]*SF[4] + P[2][5]*SF[7] - P[11][5]*SF[11] + P[10][5]*SPP[7] - (P[12][5]*q0)/2 + SF[2]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) + SF[1]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) + SF[3]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) - SPP[0]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SPP[3]*(P[3][13] + P[0][13]*SF[5] + P[1][13]*SF[4] + P[2][13]*SF[7] - P[11][13]*SF[11] + P[10][13]*SPP[7] - (P[12][13]*q0)/2);
+ nextP[3][6] = P[3][6] + P[0][6]*SF[5] + P[1][6]*SF[4] + P[2][6]*SF[7] - P[11][6]*SF[11] + P[10][6]*SPP[7] - (P[12][6]*q0)/2 + SF[2]*(P[3][1] + P[0][1]*SF[5] + P[1][1]*SF[4] + P[2][1]*SF[7] - P[11][1]*SF[11] + P[10][1]*SPP[7] - (P[12][1]*q0)/2) + SF[1]*(P[3][3] + P[0][3]*SF[5] + P[1][3]*SF[4] + P[2][3]*SF[7] - P[11][3]*SF[11] + P[10][3]*SPP[7] - (P[12][3]*q0)/2) + SPP[0]*(P[3][0] + P[0][0]*SF[5] + P[1][0]*SF[4] + P[2][0]*SF[7] - P[11][0]*SF[11] + P[10][0]*SPP[7] - (P[12][0]*q0)/2) - SPP[1]*(P[3][2] + P[0][2]*SF[5] + P[1][2]*SF[4] + P[2][2]*SF[7] - P[11][2]*SF[11] + P[10][2]*SPP[7] - (P[12][2]*q0)/2) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[3][13] + P[0][13]*SF[5] + P[1][13]*SF[4] + P[2][13]*SF[7] - P[11][13]*SF[11] + P[10][13]*SPP[7] - (P[12][13]*q0)/2);
+ nextP[3][7] = P[3][7] + P[0][7]*SF[5] + P[1][7]*SF[4] + P[2][7]*SF[7] - P[11][7]*SF[11] + P[10][7]*SPP[7] - (P[12][7]*q0)/2 + dt*(P[3][4] + P[0][4]*SF[5] + P[1][4]*SF[4] + P[2][4]*SF[7] - P[11][4]*SF[11] + P[10][4]*SPP[7] - (P[12][4]*q0)/2);
+ nextP[3][8] = P[3][8] + P[0][8]*SF[5] + P[1][8]*SF[4] + P[2][8]*SF[7] - P[11][8]*SF[11] + P[10][8]*SPP[7] - (P[12][8]*q0)/2 + dt*(P[3][5] + P[0][5]*SF[5] + P[1][5]*SF[4] + P[2][5]*SF[7] - P[11][5]*SF[11] + P[10][5]*SPP[7] - (P[12][5]*q0)/2);
+ nextP[3][9] = P[3][9] + P[0][9]*SF[5] + P[1][9]*SF[4] + P[2][9]*SF[7] - P[11][9]*SF[11] + P[10][9]*SPP[7] - (P[12][9]*q0)/2 + dt*(P[3][6] + P[0][6]*SF[5] + P[1][6]*SF[4] + P[2][6]*SF[7] - P[11][6]*SF[11] + P[10][6]*SPP[7] - (P[12][6]*q0)/2);
+ nextP[3][10] = P[3][10] + P[0][10]*SF[5] + P[1][10]*SF[4] + P[2][10]*SF[7] - P[11][10]*SF[11] + P[10][10]*SPP[7] - (P[12][10]*q0)/2;
+ nextP[3][11] = P[3][11] + P[0][11]*SF[5] + P[1][11]*SF[4] + P[2][11]*SF[7] - P[11][11]*SF[11] + P[10][11]*SPP[7] - (P[12][11]*q0)/2;
+ nextP[3][12] = P[3][12] + P[0][12]*SF[5] + P[1][12]*SF[4] + P[2][12]*SF[7] - P[11][12]*SF[11] + P[10][12]*SPP[7] - (P[12][12]*q0)/2;
+ nextP[3][13] = P[3][13] + P[0][13]*SF[5] + P[1][13]*SF[4] + P[2][13]*SF[7] - P[11][13]*SF[11] + P[10][13]*SPP[7] - (P[12][13]*q0)/2;
+ nextP[3][14] = P[3][14] + P[0][14]*SF[5] + P[1][14]*SF[4] + P[2][14]*SF[7] - P[11][14]*SF[11] + P[10][14]*SPP[7] - (P[12][14]*q0)/2;
+ nextP[3][15] = P[3][15] + P[0][15]*SF[5] + P[1][15]*SF[4] + P[2][15]*SF[7] - P[11][15]*SF[11] + P[10][15]*SPP[7] - (P[12][15]*q0)/2;
+ nextP[3][16] = P[3][16] + P[0][16]*SF[5] + P[1][16]*SF[4] + P[2][16]*SF[7] - P[11][16]*SF[11] + P[10][16]*SPP[7] - (P[12][16]*q0)/2;
+ nextP[3][17] = P[3][17] + P[0][17]*SF[5] + P[1][17]*SF[4] + P[2][17]*SF[7] - P[11][17]*SF[11] + P[10][17]*SPP[7] - (P[12][17]*q0)/2;
+ nextP[3][18] = P[3][18] + P[0][18]*SF[5] + P[1][18]*SF[4] + P[2][18]*SF[7] - P[11][18]*SF[11] + P[10][18]*SPP[7] - (P[12][18]*q0)/2;
+ nextP[3][19] = P[3][19] + P[0][19]*SF[5] + P[1][19]*SF[4] + P[2][19]*SF[7] - P[11][19]*SF[11] + P[10][19]*SPP[7] - (P[12][19]*q0)/2;
+ nextP[3][20] = P[3][20] + P[0][20]*SF[5] + P[1][20]*SF[4] + P[2][20]*SF[7] - P[11][20]*SF[11] + P[10][20]*SPP[7] - (P[12][20]*q0)/2;
+ nextP[3][21] = P[3][21] + P[0][21]*SF[5] + P[1][21]*SF[4] + P[2][21]*SF[7] - P[11][21]*SF[11] + P[10][21]*SPP[7] - (P[12][21]*q0)/2;
+ nextP[3][22] = P[3][22] + P[0][22]*SF[5] + P[1][22]*SF[4] + P[2][22]*SF[7] - P[11][22]*SF[11] + P[10][22]*SPP[7] - (P[12][22]*q0)/2;
+ nextP[4][0] = P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4] + SF[7]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[9]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) + SF[8]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SF[11]*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]) + SPP[7]*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]) + SPP[6]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]);
+ nextP[4][1] = P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4] + SF[6]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[5]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) + SF[9]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SPP[6]*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]) - SPP[7]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]) - (q0*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]))/2;
+ nextP[4][2] = P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4] + SF[4]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[8]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[6]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SF[11]*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]) - SPP[6]*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]) - (q0*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]))/2;
+ nextP[4][3] = P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4] + SF[5]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[4]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[7]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) - SF[11]*(P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4]) + SPP[7]*(P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4]) - (q0*(P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4]))/2;
+ nextP[4][4] = P[4][4] + P[0][4]*SF[3] + P[1][4]*SF[1] + P[2][4]*SPP[0] - P[3][4]*SPP[2] - P[13][4]*SPP[4] + dvyCov*sq(SG[7] - 2*q0*q3) + dvzCov*sq(SG[6] + 2*q0*q2) + SF[3]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[1]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SPP[0]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) - SPP[2]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) - SPP[4]*(P[4][13] + P[0][13]*SF[3] + P[1][13]*SF[1] + P[2][13]*SPP[0] - P[3][13]*SPP[2] - P[13][13]*SPP[4]) + dvxCov*sq(SG[1] + SG[2] - SG[3] - SG[4]);
+ nextP[4][5] = P[4][5] + SQ[2] + P[0][5]*SF[3] + P[1][5]*SF[1] + P[2][5]*SPP[0] - P[3][5]*SPP[2] - P[13][5]*SPP[4] + SF[2]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) + SF[1]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) + SF[3]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) - SPP[0]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SPP[3]*(P[4][13] + P[0][13]*SF[3] + P[1][13]*SF[1] + P[2][13]*SPP[0] - P[3][13]*SPP[2] - P[13][13]*SPP[4]);
+ nextP[4][6] = P[4][6] + SQ[1] + P[0][6]*SF[3] + P[1][6]*SF[1] + P[2][6]*SPP[0] - P[3][6]*SPP[2] - P[13][6]*SPP[4] + SF[2]*(P[4][1] + P[0][1]*SF[3] + P[1][1]*SF[1] + P[2][1]*SPP[0] - P[3][1]*SPP[2] - P[13][1]*SPP[4]) + SF[1]*(P[4][3] + P[0][3]*SF[3] + P[1][3]*SF[1] + P[2][3]*SPP[0] - P[3][3]*SPP[2] - P[13][3]*SPP[4]) + SPP[0]*(P[4][0] + P[0][0]*SF[3] + P[1][0]*SF[1] + P[2][0]*SPP[0] - P[3][0]*SPP[2] - P[13][0]*SPP[4]) - SPP[1]*(P[4][2] + P[0][2]*SF[3] + P[1][2]*SF[1] + P[2][2]*SPP[0] - P[3][2]*SPP[2] - P[13][2]*SPP[4]) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[4][13] + P[0][13]*SF[3] + P[1][13]*SF[1] + P[2][13]*SPP[0] - P[3][13]*SPP[2] - P[13][13]*SPP[4]);
+ nextP[4][7] = P[4][7] + P[0][7]*SF[3] + P[1][7]*SF[1] + P[2][7]*SPP[0] - P[3][7]*SPP[2] - P[13][7]*SPP[4] + dt*(P[4][4] + P[0][4]*SF[3] + P[1][4]*SF[1] + P[2][4]*SPP[0] - P[3][4]*SPP[2] - P[13][4]*SPP[4]);
+ nextP[4][8] = P[4][8] + P[0][8]*SF[3] + P[1][8]*SF[1] + P[2][8]*SPP[0] - P[3][8]*SPP[2] - P[13][8]*SPP[4] + dt*(P[4][5] + P[0][5]*SF[3] + P[1][5]*SF[1] + P[2][5]*SPP[0] - P[3][5]*SPP[2] - P[13][5]*SPP[4]);
+ nextP[4][9] = P[4][9] + P[0][9]*SF[3] + P[1][9]*SF[1] + P[2][9]*SPP[0] - P[3][9]*SPP[2] - P[13][9]*SPP[4] + dt*(P[4][6] + P[0][6]*SF[3] + P[1][6]*SF[1] + P[2][6]*SPP[0] - P[3][6]*SPP[2] - P[13][6]*SPP[4]);
+ nextP[4][10] = P[4][10] + P[0][10]*SF[3] + P[1][10]*SF[1] + P[2][10]*SPP[0] - P[3][10]*SPP[2] - P[13][10]*SPP[4];
+ nextP[4][11] = P[4][11] + P[0][11]*SF[3] + P[1][11]*SF[1] + P[2][11]*SPP[0] - P[3][11]*SPP[2] - P[13][11]*SPP[4];
+ nextP[4][12] = P[4][12] + P[0][12]*SF[3] + P[1][12]*SF[1] + P[2][12]*SPP[0] - P[3][12]*SPP[2] - P[13][12]*SPP[4];
+ nextP[4][13] = P[4][13] + P[0][13]*SF[3] + P[1][13]*SF[1] + P[2][13]*SPP[0] - P[3][13]*SPP[2] - P[13][13]*SPP[4];
+ nextP[4][14] = P[4][14] + P[0][14]*SF[3] + P[1][14]*SF[1] + P[2][14]*SPP[0] - P[3][14]*SPP[2] - P[13][14]*SPP[4];
+ nextP[4][15] = P[4][15] + P[0][15]*SF[3] + P[1][15]*SF[1] + P[2][15]*SPP[0] - P[3][15]*SPP[2] - P[13][15]*SPP[4];
+ nextP[4][16] = P[4][16] + P[0][16]*SF[3] + P[1][16]*SF[1] + P[2][16]*SPP[0] - P[3][16]*SPP[2] - P[13][16]*SPP[4];
+ nextP[4][17] = P[4][17] + P[0][17]*SF[3] + P[1][17]*SF[1] + P[2][17]*SPP[0] - P[3][17]*SPP[2] - P[13][17]*SPP[4];
+ nextP[4][18] = P[4][18] + P[0][18]*SF[3] + P[1][18]*SF[1] + P[2][18]*SPP[0] - P[3][18]*SPP[2] - P[13][18]*SPP[4];
+ nextP[4][19] = P[4][19] + P[0][19]*SF[3] + P[1][19]*SF[1] + P[2][19]*SPP[0] - P[3][19]*SPP[2] - P[13][19]*SPP[4];
+ nextP[4][20] = P[4][20] + P[0][20]*SF[3] + P[1][20]*SF[1] + P[2][20]*SPP[0] - P[3][20]*SPP[2] - P[13][20]*SPP[4];
+ nextP[4][21] = P[4][21] + P[0][21]*SF[3] + P[1][21]*SF[1] + P[2][21]*SPP[0] - P[3][21]*SPP[2] - P[13][21]*SPP[4];
+ nextP[4][22] = P[4][22] + P[0][22]*SF[3] + P[1][22]*SF[1] + P[2][22]*SPP[0] - P[3][22]*SPP[2] - P[13][22]*SPP[4];
+ nextP[5][0] = P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3] + SF[7]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[9]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) + SF[8]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SF[11]*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]) + SPP[7]*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]) + SPP[6]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]);
+ nextP[5][1] = P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3] + SF[6]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[5]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) + SF[9]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SPP[6]*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]) - SPP[7]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]) - (q0*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]))/2;
+ nextP[5][2] = P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3] + SF[4]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[8]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[6]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SF[11]*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]) - SPP[6]*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]) - (q0*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]))/2;
+ nextP[5][3] = P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3] + SF[5]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[4]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[7]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) - SF[11]*(P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3]) + SPP[7]*(P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3]) - (q0*(P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3]))/2;
+ nextP[5][4] = P[5][4] + SQ[2] + P[0][4]*SF[2] + P[2][4]*SF[1] + P[3][4]*SF[3] - P[1][4]*SPP[0] + P[13][4]*SPP[3] + SF[3]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[1]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SPP[0]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) - SPP[2]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) - SPP[4]*(P[5][13] + P[0][13]*SF[2] + P[2][13]*SF[1] + P[3][13]*SF[3] - P[1][13]*SPP[0] + P[13][13]*SPP[3]);
+ nextP[5][5] = P[5][5] + P[0][5]*SF[2] + P[2][5]*SF[1] + P[3][5]*SF[3] - P[1][5]*SPP[0] + P[13][5]*SPP[3] + dvxCov*sq(SG[7] + 2*q0*q3) + dvzCov*sq(SG[5] - 2*q0*q1) + SF[2]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) + SF[1]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) + SF[3]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) - SPP[0]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SPP[3]*(P[5][13] + P[0][13]*SF[2] + P[2][13]*SF[1] + P[3][13]*SF[3] - P[1][13]*SPP[0] + P[13][13]*SPP[3]) + dvyCov*sq(SG[1] - SG[2] + SG[3] - SG[4]);
+ nextP[5][6] = P[5][6] + SQ[0] + P[0][6]*SF[2] + P[2][6]*SF[1] + P[3][6]*SF[3] - P[1][6]*SPP[0] + P[13][6]*SPP[3] + SF[2]*(P[5][1] + P[0][1]*SF[2] + P[2][1]*SF[1] + P[3][1]*SF[3] - P[1][1]*SPP[0] + P[13][1]*SPP[3]) + SF[1]*(P[5][3] + P[0][3]*SF[2] + P[2][3]*SF[1] + P[3][3]*SF[3] - P[1][3]*SPP[0] + P[13][3]*SPP[3]) + SPP[0]*(P[5][0] + P[0][0]*SF[2] + P[2][0]*SF[1] + P[3][0]*SF[3] - P[1][0]*SPP[0] + P[13][0]*SPP[3]) - SPP[1]*(P[5][2] + P[0][2]*SF[2] + P[2][2]*SF[1] + P[3][2]*SF[3] - P[1][2]*SPP[0] + P[13][2]*SPP[3]) - (sq(q0) - sq(q1) - sq(q2) + sq(q3))*(P[5][13] + P[0][13]*SF[2] + P[2][13]*SF[1] + P[3][13]*SF[3] - P[1][13]*SPP[0] + P[13][13]*SPP[3]);
+ nextP[5][7] = P[5][7] + P[0][7]*SF[2] + P[2][7]*SF[1] + P[3][7]*SF[3] - P[1][7]*SPP[0] + P[13][7]*SPP[3] + dt*(P[5][4] + P[0][4]*SF[2] + P[2][4]*SF[1] + P[3][4]*SF[3] - P[1][4]*SPP[0] + P[13][4]*SPP[3]);
+ nextP[5][8] = P[5][8] + P[0][8]*SF[2] + P[2][8]*SF[1] + P[3][8]*SF[3] - P[1][8]*SPP[0] + P[13][8]*SPP[3] + dt*(P[5][5] + P[0][5]*SF[2] + P[2][5]*SF[1] + P[3][5]*SF[3] - P[1][5]*SPP[0] + P[13][5]*SPP[3]);
+ nextP[5][9] = P[5][9] + P[0][9]*SF[2] + P[2][9]*SF[1] + P[3][9]*SF[3] - P[1][9]*SPP[0] + P[13][9]*SPP[3] + dt*(P[5][6] + P[0][6]*SF[2] + P[2][6]*SF[1] + P[3][6]*SF[3] - P[1][6]*SPP[0] + P[13][6]*SPP[3]);
+ nextP[5][10] = P[5][10] + P[0][10]*SF[2] + P[2][10]*SF[1] + P[3][10]*SF[3] - P[1][10]*SPP[0] + P[13][10]*SPP[3];
+ nextP[5][11] = P[5][11] + P[0][11]*SF[2] + P[2][11]*SF[1] + P[3][11]*SF[3] - P[1][11]*SPP[0] + P[13][11]*SPP[3];
+ nextP[5][12] = P[5][12] + P[0][12]*SF[2] + P[2][12]*SF[1] + P[3][12]*SF[3] - P[1][12]*SPP[0] + P[13][12]*SPP[3];
+ nextP[5][13] = P[5][13] + P[0][13]*SF[2] + P[2][13]*SF[1] + P[3][13]*SF[3] - P[1][13]*SPP[0] + P[13][13]*SPP[3];
+ nextP[5][14] = P[5][14] + P[0][14]*SF[2] + P[2][14]*SF[1] + P[3][14]*SF[3] - P[1][14]*SPP[0] + P[13][14]*SPP[3];
+ nextP[5][15] = P[5][15] + P[0][15]*SF[2] + P[2][15]*SF[1] + P[3][15]*SF[3] - P[1][15]*SPP[0] + P[13][15]*SPP[3];
+ nextP[5][16] = P[5][16] + P[0][16]*SF[2] + P[2][16]*SF[1] + P[3][16]*SF[3] - P[1][16]*SPP[0] + P[13][16]*SPP[3];
+ nextP[5][17] = P[5][17] + P[0][17]*SF[2] + P[2][17]*SF[1] + P[3][17]*SF[3] - P[1][17]*SPP[0] + P[13][17]*SPP[3];
+ nextP[5][18] = P[5][18] + P[0][18]*SF[2] + P[2][18]*SF[1] + P[3][18]*SF[3] - P[1][18]*SPP[0] + P[13][18]*SPP[3];
+ nextP[5][19] = P[5][19] + P[0][19]*SF[2] + P[2][19]*SF[1] + P[3][19]*SF[3] - P[1][19]*SPP[0] + P[13][19]*SPP[3];
+ nextP[5][20] = P[5][20] + P[0][20]*SF[2] + P[2][20]*SF[1] + P[3][20]*SF[3] - P[1][20]*SPP[0] + P[13][20]*SPP[3];
+ nextP[5][21] = P[5][21] + P[0][21]*SF[2] + P[2][21]*SF[1] + P[3][21]*SF[3] - P[1][21]*SPP[0] + P[13][21]*SPP[3];
+ nextP[5][22] = P[5][22] + P[0][22]*SF[2] + P[2][22]*SF[1] + P[3][22]*SF[3] - P[1][22]*SPP[0] + P[13][22]*SPP[3];
+ nextP[6][0] = P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[7]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[9]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[8]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[11]*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[7]*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[6]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)));
+ nextP[6][1] = P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[6]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[5]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[9]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[6]*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[7]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - (q0*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))))/2;
+ nextP[6][2] = P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[4]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[8]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[6]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[11]*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[6]*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - (q0*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))))/2;
+ nextP[6][3] = P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[5]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[4]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[7]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SF[11]*(P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[7]*(P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - (q0*(P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))))/2;
+ nextP[6][4] = P[6][4] + SQ[1] + P[1][4]*SF[2] + P[3][4]*SF[1] + P[0][4]*SPP[0] - P[2][4]*SPP[1] - P[13][4]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[3]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[1]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[0]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[2]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[4]*(P[6][13] + P[1][13]*SF[2] + P[3][13]*SF[1] + P[0][13]*SPP[0] - P[2][13]*SPP[1] - P[13][13]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)));
+ nextP[6][5] = P[6][5] + SQ[0] + P[1][5]*SF[2] + P[3][5]*SF[1] + P[0][5]*SPP[0] - P[2][5]*SPP[1] - P[13][5]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + SF[2]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[1]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[3]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[0]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[3]*(P[6][13] + P[1][13]*SF[2] + P[3][13]*SF[1] + P[0][13]*SPP[0] - P[2][13]*SPP[1] - P[13][13]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)));
+ nextP[6][6] = P[6][6] + P[1][6]*SF[2] + P[3][6]*SF[1] + P[0][6]*SPP[0] - P[2][6]*SPP[1] - P[13][6]*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + dvxCov*sq(SG[6] - 2*q0*q2) + dvyCov*sq(SG[5] + 2*q0*q1) - SPP[5]*(P[6][13] + P[1][13]*SF[2] + P[3][13]*SF[1] + P[0][13]*SPP[0] - P[2][13]*SPP[1] - P[13][13]*SPP[5]) + SF[2]*(P[6][1] + P[1][1]*SF[2] + P[3][1]*SF[1] + P[0][1]*SPP[0] - P[2][1]*SPP[1] - P[13][1]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SF[1]*(P[6][3] + P[1][3]*SF[2] + P[3][3]*SF[1] + P[0][3]*SPP[0] - P[2][3]*SPP[1] - P[13][3]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + SPP[0]*(P[6][0] + P[1][0]*SF[2] + P[3][0]*SF[1] + P[0][0]*SPP[0] - P[2][0]*SPP[1] - P[13][0]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) - SPP[1]*(P[6][2] + P[1][2]*SF[2] + P[3][2]*SF[1] + P[0][2]*SPP[0] - P[2][2]*SPP[1] - P[13][2]*(sq(q0) - sq(q1) - sq(q2) + sq(q3))) + dvzCov*sq(SG[1] - SG[2] - SG[3] + SG[4]);
+ nextP[6][7] = P[6][7] + P[1][7]*SF[2] + P[3][7]*SF[1] + P[0][7]*SPP[0] - P[2][7]*SPP[1] - P[13][7]*SPP[5] + dt*(P[6][4] + P[1][4]*SF[2] + P[3][4]*SF[1] + P[0][4]*SPP[0] - P[2][4]*SPP[1] - P[13][4]*SPP[5]);
+ nextP[6][8] = P[6][8] + P[1][8]*SF[2] + P[3][8]*SF[1] + P[0][8]*SPP[0] - P[2][8]*SPP[1] - P[13][8]*SPP[5] + dt*(P[6][5] + P[1][5]*SF[2] + P[3][5]*SF[1] + P[0][5]*SPP[0] - P[2][5]*SPP[1] - P[13][5]*SPP[5]);
+ nextP[6][9] = P[6][9] + P[1][9]*SF[2] + P[3][9]*SF[1] + P[0][9]*SPP[0] - P[2][9]*SPP[1] - P[13][9]*SPP[5] + dt*(P[6][6] + P[1][6]*SF[2] + P[3][6]*SF[1] + P[0][6]*SPP[0] - P[2][6]*SPP[1] - P[13][6]*SPP[5]);
+ nextP[6][10] = P[6][10] + P[1][10]*SF[2] + P[3][10]*SF[1] + P[0][10]*SPP[0] - P[2][10]*SPP[1] - P[13][10]*SPP[5];
+ nextP[6][11] = P[6][11] + P[1][11]*SF[2] + P[3][11]*SF[1] + P[0][11]*SPP[0] - P[2][11]*SPP[1] - P[13][11]*SPP[5];
+ nextP[6][12] = P[6][12] + P[1][12]*SF[2] + P[3][12]*SF[1] + P[0][12]*SPP[0] - P[2][12]*SPP[1] - P[13][12]*SPP[5];
+ nextP[6][13] = P[6][13] + P[1][13]*SF[2] + P[3][13]*SF[1] + P[0][13]*SPP[0] - P[2][13]*SPP[1] - P[13][13]*SPP[5];
+ nextP[6][14] = P[6][14] + P[1][14]*SF[2] + P[3][14]*SF[1] + P[0][14]*SPP[0] - P[2][14]*SPP[1] - P[13][14]*SPP[5];
+ nextP[6][15] = P[6][15] + P[1][15]*SF[2] + P[3][15]*SF[1] + P[0][15]*SPP[0] - P[2][15]*SPP[1] - P[13][15]*SPP[5];
+ nextP[6][16] = P[6][16] + P[1][16]*SF[2] + P[3][16]*SF[1] + P[0][16]*SPP[0] - P[2][16]*SPP[1] - P[13][16]*SPP[5];
+ nextP[6][17] = P[6][17] + P[1][17]*SF[2] + P[3][17]*SF[1] + P[0][17]*SPP[0] - P[2][17]*SPP[1] - P[13][17]*SPP[5];
+ nextP[6][18] = P[6][18] + P[1][18]*SF[2] + P[3][18]*SF[1] + P[0][18]*SPP[0] - P[2][18]*SPP[1] - P[13][18]*SPP[5];
+ nextP[6][19] = P[6][19] + P[1][19]*SF[2] + P[3][19]*SF[1] + P[0][19]*SPP[0] - P[2][19]*SPP[1] - P[13][19]*SPP[5];
+ nextP[6][20] = P[6][20] + P[1][20]*SF[2] + P[3][20]*SF[1] + P[0][20]*SPP[0] - P[2][20]*SPP[1] - P[13][20]*SPP[5];
+ nextP[6][21] = P[6][21] + P[1][21]*SF[2] + P[3][21]*SF[1] + P[0][21]*SPP[0] - P[2][21]*SPP[1] - P[13][21]*SPP[5];
+ nextP[6][22] = P[6][22] + P[1][22]*SF[2] + P[3][22]*SF[1] + P[0][22]*SPP[0] - P[2][22]*SPP[1] - P[13][22]*SPP[5];
+ nextP[7][0] = P[7][0] + P[4][0]*dt + SF[7]*(P[7][1] + P[4][1]*dt) + SF[9]*(P[7][2] + P[4][2]*dt) + SF[8]*(P[7][3] + P[4][3]*dt) + SF[11]*(P[7][10] + P[4][10]*dt) + SPP[7]*(P[7][11] + P[4][11]*dt) + SPP[6]*(P[7][12] + P[4][12]*dt);
+ nextP[7][1] = P[7][1] + P[4][1]*dt + SF[6]*(P[7][0] + P[4][0]*dt) + SF[5]*(P[7][2] + P[4][2]*dt) + SF[9]*(P[7][3] + P[4][3]*dt) + SPP[6]*(P[7][11] + P[4][11]*dt) - SPP[7]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][10] + P[4][10]*dt))/2;
+ nextP[7][2] = P[7][2] + P[4][2]*dt + SF[4]*(P[7][0] + P[4][0]*dt) + SF[8]*(P[7][1] + P[4][1]*dt) + SF[6]*(P[7][3] + P[4][3]*dt) + SF[11]*(P[7][12] + P[4][12]*dt) - SPP[6]*(P[7][10] + P[4][10]*dt) - (q0*(P[7][11] + P[4][11]*dt))/2;
+ nextP[7][3] = P[7][3] + P[4][3]*dt + SF[5]*(P[7][0] + P[4][0]*dt) + SF[4]*(P[7][1] + P[4][1]*dt) + SF[7]*(P[7][2] + P[4][2]*dt) - SF[11]*(P[7][11] + P[4][11]*dt) + SPP[7]*(P[7][10] + P[4][10]*dt) - (q0*(P[7][12] + P[4][12]*dt))/2;
+ nextP[7][4] = P[7][4] + P[4][4]*dt + SF[1]*(P[7][1] + P[4][1]*dt) + SF[3]*(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) - SPP[4]*(P[7][13] + P[4][13]*dt);
+ nextP[7][5] = P[7][5] + P[4][5]*dt + SF[2]*(P[7][0] + P[4][0]*dt) + SF[1]*(P[7][2] + P[4][2]*dt) + SF[3]*(P[7][3] + P[4][3]*dt) - SPP[0]*(P[7][1] + P[4][1]*dt) + SPP[3]*(P[7][13] + P[4][13]*dt);
+ nextP[7][6] = P[7][6] + P[4][6]*dt + SF[2]*(P[7][1] + P[4][1]*dt) + SF[1]*(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) - SPP[5]*(P[7][13] + P[4][13]*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[7][21] = P[7][21] + P[4][21]*dt;
+ nextP[7][22] = P[7][22] + P[4][22]*dt;
+ nextP[8][0] = P[8][0] + P[5][0]*dt + SF[7]*(P[8][1] + P[5][1]*dt) + SF[9]*(P[8][2] + P[5][2]*dt) + SF[8]*(P[8][3] + P[5][3]*dt) + SF[11]*(P[8][10] + P[5][10]*dt) + SPP[7]*(P[8][11] + P[5][11]*dt) + SPP[6]*(P[8][12] + P[5][12]*dt);
+ nextP[8][1] = P[8][1] + P[5][1]*dt + SF[6]*(P[8][0] + P[5][0]*dt) + SF[5]*(P[8][2] + P[5][2]*dt) + SF[9]*(P[8][3] + P[5][3]*dt) + SPP[6]*(P[8][11] + P[5][11]*dt) - SPP[7]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][10] + P[5][10]*dt))/2;
+ nextP[8][2] = P[8][2] + P[5][2]*dt + SF[4]*(P[8][0] + P[5][0]*dt) + SF[8]*(P[8][1] + P[5][1]*dt) + SF[6]*(P[8][3] + P[5][3]*dt) + SF[11]*(P[8][12] + P[5][12]*dt) - SPP[6]*(P[8][10] + P[5][10]*dt) - (q0*(P[8][11] + P[5][11]*dt))/2;
+ nextP[8][3] = P[8][3] + P[5][3]*dt + SF[5]*(P[8][0] + P[5][0]*dt) + SF[4]*(P[8][1] + P[5][1]*dt) + SF[7]*(P[8][2] + P[5][2]*dt) - SF[11]*(P[8][11] + P[5][11]*dt) + SPP[7]*(P[8][10] + P[5][10]*dt) - (q0*(P[8][12] + P[5][12]*dt))/2;
+ nextP[8][4] = P[8][4] + P[5][4]*dt + SF[1]*(P[8][1] + P[5][1]*dt) + SF[3]*(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) - SPP[4]*(P[8][13] + P[5][13]*dt);
+ nextP[8][5] = P[8][5] + P[5][5]*dt + SF[2]*(P[8][0] + P[5][0]*dt) + SF[1]*(P[8][2] + P[5][2]*dt) + SF[3]*(P[8][3] + P[5][3]*dt) - SPP[0]*(P[8][1] + P[5][1]*dt) + SPP[3]*(P[8][13] + P[5][13]*dt);
+ nextP[8][6] = P[8][6] + P[5][6]*dt + SF[2]*(P[8][1] + P[5][1]*dt) + SF[1]*(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) - SPP[5]*(P[8][13] + P[5][13]*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[8][21] = P[8][21] + P[5][21]*dt;
+ nextP[8][22] = P[8][22] + P[5][22]*dt;
+ nextP[9][0] = P[9][0] + P[6][0]*dt + SF[7]*(P[9][1] + P[6][1]*dt) + SF[9]*(P[9][2] + P[6][2]*dt) + SF[8]*(P[9][3] + P[6][3]*dt) + SF[11]*(P[9][10] + P[6][10]*dt) + SPP[7]*(P[9][11] + P[6][11]*dt) + SPP[6]*(P[9][12] + P[6][12]*dt);
+ nextP[9][1] = P[9][1] + P[6][1]*dt + SF[6]*(P[9][0] + P[6][0]*dt) + SF[5]*(P[9][2] + P[6][2]*dt) + SF[9]*(P[9][3] + P[6][3]*dt) + SPP[6]*(P[9][11] + P[6][11]*dt) - SPP[7]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][10] + P[6][10]*dt))/2;
+ nextP[9][2] = P[9][2] + P[6][2]*dt + SF[4]*(P[9][0] + P[6][0]*dt) + SF[8]*(P[9][1] + P[6][1]*dt) + SF[6]*(P[9][3] + P[6][3]*dt) + SF[11]*(P[9][12] + P[6][12]*dt) - SPP[6]*(P[9][10] + P[6][10]*dt) - (q0*(P[9][11] + P[6][11]*dt))/2;
+ nextP[9][3] = P[9][3] + P[6][3]*dt + SF[5]*(P[9][0] + P[6][0]*dt) + SF[4]*(P[9][1] + P[6][1]*dt) + SF[7]*(P[9][2] + P[6][2]*dt) - SF[11]*(P[9][11] + P[6][11]*dt) + SPP[7]*(P[9][10] + P[6][10]*dt) - (q0*(P[9][12] + P[6][12]*dt))/2;
+ nextP[9][4] = P[9][4] + P[6][4]*dt + SF[1]*(P[9][1] + P[6][1]*dt) + SF[3]*(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) - SPP[4]*(P[9][13] + P[6][13]*dt);
+ nextP[9][5] = P[9][5] + P[6][5]*dt + SF[2]*(P[9][0] + P[6][0]*dt) + SF[1]*(P[9][2] + P[6][2]*dt) + SF[3]*(P[9][3] + P[6][3]*dt) - SPP[0]*(P[9][1] + P[6][1]*dt) + SPP[3]*(P[9][13] + P[6][13]*dt);
+ nextP[9][6] = P[9][6] + P[6][6]*dt + SF[2]*(P[9][1] + P[6][1]*dt) + SF[1]*(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) - SPP[5]*(P[9][13] + P[6][13]*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[9][21] = P[9][21] + P[6][21]*dt;
+ nextP[9][22] = P[9][22] + P[6][22]*dt;
+ nextP[10][0] = P[10][0] + P[10][1]*SF[7] + P[10][2]*SF[9] + P[10][3]*SF[8] + P[10][10]*SF[11] + P[10][11]*SPP[7] + P[10][12]*SPP[6];
+ nextP[10][1] = P[10][1] + P[10][0]*SF[6] + P[10][2]*SF[5] + P[10][3]*SF[9] + P[10][11]*SPP[6] - P[10][12]*SPP[7] - (P[10][10]*q0)/2;
+ nextP[10][2] = P[10][2] + P[10][0]*SF[4] + P[10][1]*SF[8] + P[10][3]*SF[6] + P[10][12]*SF[11] - P[10][10]*SPP[6] - (P[10][11]*q0)/2;
+ nextP[10][3] = P[10][3] + P[10][0]*SF[5] + P[10][1]*SF[4] + P[10][2]*SF[7] - P[10][11]*SF[11] + P[10][10]*SPP[7] - (P[10][12]*q0)/2;
+ nextP[10][4] = P[10][4] + P[10][1]*SF[1] + P[10][0]*SF[3] + P[10][2]*SPP[0] - P[10][3]*SPP[2] - P[10][13]*SPP[4];
+ nextP[10][5] = P[10][5] + P[10][0]*SF[2] + P[10][2]*SF[1] + P[10][3]*SF[3] - P[10][1]*SPP[0] + P[10][13]*SPP[3];
+ nextP[10][6] = P[10][6] + P[10][1]*SF[2] + P[10][3]*SF[1] + P[10][0]*SPP[0] - P[10][2]*SPP[1] - P[10][13]*SPP[5];
+ 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[10][21] = P[10][21];
+ nextP[10][22] = P[10][22];
+ nextP[11][0] = P[11][0] + P[11][1]*SF[7] + P[11][2]*SF[9] + P[11][3]*SF[8] + P[11][10]*SF[11] + P[11][11]*SPP[7] + P[11][12]*SPP[6];
+ nextP[11][1] = P[11][1] + P[11][0]*SF[6] + P[11][2]*SF[5] + P[11][3]*SF[9] + P[11][11]*SPP[6] - P[11][12]*SPP[7] - (P[11][10]*q0)/2;
+ nextP[11][2] = P[11][2] + P[11][0]*SF[4] + P[11][1]*SF[8] + P[11][3]*SF[6] + P[11][12]*SF[11] - P[11][10]*SPP[6] - (P[11][11]*q0)/2;
+ nextP[11][3] = P[11][3] + P[11][0]*SF[5] + P[11][1]*SF[4] + P[11][2]*SF[7] - P[11][11]*SF[11] + P[11][10]*SPP[7] - (P[11][12]*q0)/2;
+ nextP[11][4] = P[11][4] + P[11][1]*SF[1] + P[11][0]*SF[3] + P[11][2]*SPP[0] - P[11][3]*SPP[2] - P[11][13]*SPP[4];
+ nextP[11][5] = P[11][5] + P[11][0]*SF[2] + P[11][2]*SF[1] + P[11][3]*SF[3] - P[11][1]*SPP[0] + P[11][13]*SPP[3];
+ nextP[11][6] = P[11][6] + P[11][1]*SF[2] + P[11][3]*SF[1] + P[11][0]*SPP[0] - P[11][2]*SPP[1] - P[11][13]*SPP[5];
+ 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[11][21] = P[11][21];
+ nextP[11][22] = P[11][22];
+ nextP[12][0] = P[12][0] + P[12][1]*SF[7] + P[12][2]*SF[9] + P[12][3]*SF[8] + P[12][10]*SF[11] + P[12][11]*SPP[7] + P[12][12]*SPP[6];
+ nextP[12][1] = P[12][1] + P[12][0]*SF[6] + P[12][2]*SF[5] + P[12][3]*SF[9] + P[12][11]*SPP[6] - P[12][12]*SPP[7] - (P[12][10]*q0)/2;
+ nextP[12][2] = P[12][2] + P[12][0]*SF[4] + P[12][1]*SF[8] + P[12][3]*SF[6] + P[12][12]*SF[11] - P[12][10]*SPP[6] - (P[12][11]*q0)/2;
+ nextP[12][3] = P[12][3] + P[12][0]*SF[5] + P[12][1]*SF[4] + P[12][2]*SF[7] - P[12][11]*SF[11] + P[12][10]*SPP[7] - (P[12][12]*q0)/2;
+ nextP[12][4] = P[12][4] + P[12][1]*SF[1] + P[12][0]*SF[3] + P[12][2]*SPP[0] - P[12][3]*SPP[2] - P[12][13]*SPP[4];
+ nextP[12][5] = P[12][5] + P[12][0]*SF[2] + P[12][2]*SF[1] + P[12][3]*SF[3] - P[12][1]*SPP[0] + P[12][13]*SPP[3];
+ nextP[12][6] = P[12][6] + P[12][1]*SF[2] + P[12][3]*SF[1] + P[12][0]*SPP[0] - P[12][2]*SPP[1] - P[12][13]*SPP[5];
+ 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[12][21] = P[12][21];
+ nextP[12][22] = P[12][22];
+ nextP[13][0] = P[13][0] + P[13][1]*SF[7] + P[13][2]*SF[9] + P[13][3]*SF[8] + P[13][10]*SF[11] + P[13][11]*SPP[7] + P[13][12]*SPP[6];
+ nextP[13][1] = P[13][1] + P[13][0]*SF[6] + P[13][2]*SF[5] + P[13][3]*SF[9] + P[13][11]*SPP[6] - P[13][12]*SPP[7] - (P[13][10]*q0)/2;
+ nextP[13][2] = P[13][2] + P[13][0]*SF[4] + P[13][1]*SF[8] + P[13][3]*SF[6] + P[13][12]*SF[11] - P[13][10]*SPP[6] - (P[13][11]*q0)/2;
+ nextP[13][3] = P[13][3] + P[13][0]*SF[5] + P[13][1]*SF[4] + P[13][2]*SF[7] - P[13][11]*SF[11] + P[13][10]*SPP[7] - (P[13][12]*q0)/2;
+ nextP[13][4] = P[13][4] + P[13][1]*SF[1] + P[13][0]*SF[3] + P[13][2]*SPP[0] - P[13][3]*SPP[2] - P[13][13]*SPP[4];
+ nextP[13][5] = P[13][5] + P[13][0]*SF[2] + P[13][2]*SF[1] + P[13][3]*SF[3] - P[13][1]*SPP[0] + P[13][13]*SPP[3];
+ nextP[13][6] = P[13][6] + P[13][1]*SF[2] + P[13][3]*SF[1] + P[13][0]*SPP[0] - P[13][2]*SPP[1] - P[13][13]*SPP[5];
+ 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[13][21] = P[13][21];
+ nextP[13][22] = P[13][22];
+ nextP[14][0] = P[14][0] + P[14][1]*SF[7] + P[14][2]*SF[9] + P[14][3]*SF[8] + P[14][10]*SF[11] + P[14][11]*SPP[7] + P[14][12]*SPP[6];
+ nextP[14][1] = P[14][1] + P[14][0]*SF[6] + P[14][2]*SF[5] + P[14][3]*SF[9] + P[14][11]*SPP[6] - P[14][12]*SPP[7] - (P[14][10]*q0)/2;
+ nextP[14][2] = P[14][2] + P[14][0]*SF[4] + P[14][1]*SF[8] + P[14][3]*SF[6] + P[14][12]*SF[11] - P[14][10]*SPP[6] - (P[14][11]*q0)/2;
+ nextP[14][3] = P[14][3] + P[14][0]*SF[5] + P[14][1]*SF[4] + P[14][2]*SF[7] - P[14][11]*SF[11] + P[14][10]*SPP[7] - (P[14][12]*q0)/2;
+ nextP[14][4] = P[14][4] + P[14][1]*SF[1] + P[14][0]*SF[3] + P[14][2]*SPP[0] - P[14][3]*SPP[2] - P[14][13]*SPP[4];
+ nextP[14][5] = P[14][5] + P[14][0]*SF[2] + P[14][2]*SF[1] + P[14][3]*SF[3] - P[14][1]*SPP[0] + P[14][13]*SPP[3];
+ nextP[14][6] = P[14][6] + P[14][1]*SF[2] + P[14][3]*SF[1] + P[14][0]*SPP[0] - P[14][2]*SPP[1] - P[14][13]*SPP[5];
+ 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[14][21] = P[14][21];
+ nextP[14][22] = P[14][22];
+ nextP[15][0] = P[15][0] + P[15][1]*SF[7] + P[15][2]*SF[9] + P[15][3]*SF[8] + P[15][10]*SF[11] + P[15][11]*SPP[7] + P[15][12]*SPP[6];
+ nextP[15][1] = P[15][1] + P[15][0]*SF[6] + P[15][2]*SF[5] + P[15][3]*SF[9] + P[15][11]*SPP[6] - P[15][12]*SPP[7] - (P[15][10]*q0)/2;
+ nextP[15][2] = P[15][2] + P[15][0]*SF[4] + P[15][1]*SF[8] + P[15][3]*SF[6] + P[15][12]*SF[11] - P[15][10]*SPP[6] - (P[15][11]*q0)/2;
+ nextP[15][3] = P[15][3] + P[15][0]*SF[5] + P[15][1]*SF[4] + P[15][2]*SF[7] - P[15][11]*SF[11] + P[15][10]*SPP[7] - (P[15][12]*q0)/2;
+ nextP[15][4] = P[15][4] + P[15][1]*SF[1] + P[15][0]*SF[3] + P[15][2]*SPP[0] - P[15][3]*SPP[2] - P[15][13]*SPP[4];
+ nextP[15][5] = P[15][5] + P[15][0]*SF[2] + P[15][2]*SF[1] + P[15][3]*SF[3] - P[15][1]*SPP[0] + P[15][13]*SPP[3];
+ nextP[15][6] = P[15][6] + P[15][1]*SF[2] + P[15][3]*SF[1] + P[15][0]*SPP[0] - P[15][2]*SPP[1] - P[15][13]*SPP[5];
+ 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[15][21] = P[15][21];
+ nextP[15][22] = P[15][22];
+ nextP[16][0] = P[16][0] + P[16][1]*SF[7] + P[16][2]*SF[9] + P[16][3]*SF[8] + P[16][10]*SF[11] + P[16][11]*SPP[7] + P[16][12]*SPP[6];
+ nextP[16][1] = P[16][1] + P[16][0]*SF[6] + P[16][2]*SF[5] + P[16][3]*SF[9] + P[16][11]*SPP[6] - P[16][12]*SPP[7] - (P[16][10]*q0)/2;
+ nextP[16][2] = P[16][2] + P[16][0]*SF[4] + P[16][1]*SF[8] + P[16][3]*SF[6] + P[16][12]*SF[11] - P[16][10]*SPP[6] - (P[16][11]*q0)/2;
+ nextP[16][3] = P[16][3] + P[16][0]*SF[5] + P[16][1]*SF[4] + P[16][2]*SF[7] - P[16][11]*SF[11] + P[16][10]*SPP[7] - (P[16][12]*q0)/2;
+ nextP[16][4] = P[16][4] + P[16][1]*SF[1] + P[16][0]*SF[3] + P[16][2]*SPP[0] - P[16][3]*SPP[2] - P[16][13]*SPP[4];
+ nextP[16][5] = P[16][5] + P[16][0]*SF[2] + P[16][2]*SF[1] + P[16][3]*SF[3] - P[16][1]*SPP[0] + P[16][13]*SPP[3];
+ nextP[16][6] = P[16][6] + P[16][1]*SF[2] + P[16][3]*SF[1] + P[16][0]*SPP[0] - P[16][2]*SPP[1] - P[16][13]*SPP[5];
+ 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[16][21] = P[16][21];
+ nextP[16][22] = P[16][22];
+ nextP[17][0] = P[17][0] + P[17][1]*SF[7] + P[17][2]*SF[9] + P[17][3]*SF[8] + P[17][10]*SF[11] + P[17][11]*SPP[7] + P[17][12]*SPP[6];
+ nextP[17][1] = P[17][1] + P[17][0]*SF[6] + P[17][2]*SF[5] + P[17][3]*SF[9] + P[17][11]*SPP[6] - P[17][12]*SPP[7] - (P[17][10]*q0)/2;
+ nextP[17][2] = P[17][2] + P[17][0]*SF[4] + P[17][1]*SF[8] + P[17][3]*SF[6] + P[17][12]*SF[11] - P[17][10]*SPP[6] - (P[17][11]*q0)/2;
+ nextP[17][3] = P[17][3] + P[17][0]*SF[5] + P[17][1]*SF[4] + P[17][2]*SF[7] - P[17][11]*SF[11] + P[17][10]*SPP[7] - (P[17][12]*q0)/2;
+ nextP[17][4] = P[17][4] + P[17][1]*SF[1] + P[17][0]*SF[3] + P[17][2]*SPP[0] - P[17][3]*SPP[2] - P[17][13]*SPP[4];
+ nextP[17][5] = P[17][5] + P[17][0]*SF[2] + P[17][2]*SF[1] + P[17][3]*SF[3] - P[17][1]*SPP[0] + P[17][13]*SPP[3];
+ nextP[17][6] = P[17][6] + P[17][1]*SF[2] + P[17][3]*SF[1] + P[17][0]*SPP[0] - P[17][2]*SPP[1] - P[17][13]*SPP[5];
+ 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[17][21] = P[17][21];
+ nextP[17][22] = P[17][22];
+ nextP[18][0] = P[18][0] + P[18][1]*SF[7] + P[18][2]*SF[9] + P[18][3]*SF[8] + P[18][10]*SF[11] + P[18][11]*SPP[7] + P[18][12]*SPP[6];
+ nextP[18][1] = P[18][1] + P[18][0]*SF[6] + P[18][2]*SF[5] + P[18][3]*SF[9] + P[18][11]*SPP[6] - P[18][12]*SPP[7] - (P[18][10]*q0)/2;
+ nextP[18][2] = P[18][2] + P[18][0]*SF[4] + P[18][1]*SF[8] + P[18][3]*SF[6] + P[18][12]*SF[11] - P[18][10]*SPP[6] - (P[18][11]*q0)/2;
+ nextP[18][3] = P[18][3] + P[18][0]*SF[5] + P[18][1]*SF[4] + P[18][2]*SF[7] - P[18][11]*SF[11] + P[18][10]*SPP[7] - (P[18][12]*q0)/2;
+ nextP[18][4] = P[18][4] + P[18][1]*SF[1] + P[18][0]*SF[3] + P[18][2]*SPP[0] - P[18][3]*SPP[2] - P[18][13]*SPP[4];
+ nextP[18][5] = P[18][5] + P[18][0]*SF[2] + P[18][2]*SF[1] + P[18][3]*SF[3] - P[18][1]*SPP[0] + P[18][13]*SPP[3];
+ nextP[18][6] = P[18][6] + P[18][1]*SF[2] + P[18][3]*SF[1] + P[18][0]*SPP[0] - P[18][2]*SPP[1] - P[18][13]*SPP[5];
+ 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[18][21] = P[18][21];
+ nextP[18][22] = P[18][22];
+ nextP[19][0] = P[19][0] + P[19][1]*SF[7] + P[19][2]*SF[9] + P[19][3]*SF[8] + P[19][10]*SF[11] + P[19][11]*SPP[7] + P[19][12]*SPP[6];
+ nextP[19][1] = P[19][1] + P[19][0]*SF[6] + P[19][2]*SF[5] + P[19][3]*SF[9] + P[19][11]*SPP[6] - P[19][12]*SPP[7] - (P[19][10]*q0)/2;
+ nextP[19][2] = P[19][2] + P[19][0]*SF[4] + P[19][1]*SF[8] + P[19][3]*SF[6] + P[19][12]*SF[11] - P[19][10]*SPP[6] - (P[19][11]*q0)/2;
+ nextP[19][3] = P[19][3] + P[19][0]*SF[5] + P[19][1]*SF[4] + P[19][2]*SF[7] - P[19][11]*SF[11] + P[19][10]*SPP[7] - (P[19][12]*q0)/2;
+ nextP[19][4] = P[19][4] + P[19][1]*SF[1] + P[19][0]*SF[3] + P[19][2]*SPP[0] - P[19][3]*SPP[2] - P[19][13]*SPP[4];
+ nextP[19][5] = P[19][5] + P[19][0]*SF[2] + P[19][2]*SF[1] + P[19][3]*SF[3] - P[19][1]*SPP[0] + P[19][13]*SPP[3];
+ nextP[19][6] = P[19][6] + P[19][1]*SF[2] + P[19][3]*SF[1] + P[19][0]*SPP[0] - P[19][2]*SPP[1] - P[19][13]*SPP[5];
+ 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[19][21] = P[19][21];
+ nextP[19][22] = P[19][22];
+ nextP[20][0] = P[20][0] + P[20][1]*SF[7] + P[20][2]*SF[9] + P[20][3]*SF[8] + P[20][10]*SF[11] + P[20][11]*SPP[7] + P[20][12]*SPP[6];
+ nextP[20][1] = P[20][1] + P[20][0]*SF[6] + P[20][2]*SF[5] + P[20][3]*SF[9] + P[20][11]*SPP[6] - P[20][12]*SPP[7] - (P[20][10]*q0)/2;
+ nextP[20][2] = P[20][2] + P[20][0]*SF[4] + P[20][1]*SF[8] + P[20][3]*SF[6] + P[20][12]*SF[11] - P[20][10]*SPP[6] - (P[20][11]*q0)/2;
+ nextP[20][3] = P[20][3] + P[20][0]*SF[5] + P[20][1]*SF[4] + P[20][2]*SF[7] - P[20][11]*SF[11] + P[20][10]*SPP[7] - (P[20][12]*q0)/2;
+ nextP[20][4] = P[20][4] + P[20][1]*SF[1] + P[20][0]*SF[3] + P[20][2]*SPP[0] - P[20][3]*SPP[2] - P[20][13]*SPP[4];
+ nextP[20][5] = P[20][5] + P[20][0]*SF[2] + P[20][2]*SF[1] + P[20][3]*SF[3] - P[20][1]*SPP[0] + P[20][13]*SPP[3];
+ nextP[20][6] = P[20][6] + P[20][1]*SF[2] + P[20][3]*SF[1] + P[20][0]*SPP[0] - P[20][2]*SPP[1] - P[20][13]*SPP[5];
+ 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];
+ nextP[20][21] = P[20][21];
+ nextP[20][22] = P[20][22];
+ nextP[21][0] = P[21][0] + P[21][1]*SF[7] + P[21][2]*SF[9] + P[21][3]*SF[8] + P[21][10]*SF[11] + P[21][11]*SPP[7] + P[21][12]*SPP[6];
+ nextP[21][1] = P[21][1] + P[21][0]*SF[6] + P[21][2]*SF[5] + P[21][3]*SF[9] + P[21][11]*SPP[6] - P[21][12]*SPP[7] - (P[21][10]*q0)/2;
+ nextP[21][2] = P[21][2] + P[21][0]*SF[4] + P[21][1]*SF[8] + P[21][3]*SF[6] + P[21][12]*SF[11] - P[21][10]*SPP[6] - (P[21][11]*q0)/2;
+ nextP[21][3] = P[21][3] + P[21][0]*SF[5] + P[21][1]*SF[4] + P[21][2]*SF[7] - P[21][11]*SF[11] + P[21][10]*SPP[7] - (P[21][12]*q0)/2;
+ nextP[21][4] = P[21][4] + P[21][1]*SF[1] + P[21][0]*SF[3] + P[21][2]*SPP[0] - P[21][3]*SPP[2] - P[21][13]*SPP[4];
+ nextP[21][5] = P[21][5] + P[21][0]*SF[2] + P[21][2]*SF[1] + P[21][3]*SF[3] - P[21][1]*SPP[0] + P[21][13]*SPP[3];
+ nextP[21][6] = P[21][6] + P[21][1]*SF[2] + P[21][3]*SF[1] + P[21][0]*SPP[0] - P[21][2]*SPP[1] - P[21][13]*SPP[5];
+ nextP[21][7] = P[21][7] + P[21][4]*dt;
+ nextP[21][8] = P[21][8] + P[21][5]*dt;
+ nextP[21][9] = P[21][9] + P[21][6]*dt;
+ nextP[21][10] = P[21][10];
+ nextP[21][11] = P[21][11];
+ nextP[21][12] = P[21][12];
+ nextP[21][13] = P[21][13];
+ nextP[21][14] = P[21][14];
+ nextP[21][15] = P[21][15];
+ nextP[21][16] = P[21][16];
+ nextP[21][17] = P[21][17];
+ nextP[21][18] = P[21][18];
+ nextP[21][19] = P[21][19];
+ nextP[21][20] = P[21][20];
+ nextP[21][21] = P[21][21];
+ nextP[21][22] = P[21][22];
+ nextP[22][0] = P[22][0] + P[22][1]*SF[7] + P[22][2]*SF[9] + P[22][3]*SF[8] + P[22][10]*SF[11] + P[22][11]*SPP[7] + P[22][12]*SPP[6];
+ nextP[22][1] = P[22][1] + P[22][0]*SF[6] + P[22][2]*SF[5] + P[22][3]*SF[9] + P[22][11]*SPP[6] - P[22][12]*SPP[7] - (P[22][10]*q0)/2;
+ nextP[22][2] = P[22][2] + P[22][0]*SF[4] + P[22][1]*SF[8] + P[22][3]*SF[6] + P[22][12]*SF[11] - P[22][10]*SPP[6] - (P[22][11]*q0)/2;
+ nextP[22][3] = P[22][3] + P[22][0]*SF[5] + P[22][1]*SF[4] + P[22][2]*SF[7] - P[22][11]*SF[11] + P[22][10]*SPP[7] - (P[22][12]*q0)/2;
+ nextP[22][4] = P[22][4] + P[22][1]*SF[1] + P[22][0]*SF[3] + P[22][2]*SPP[0] - P[22][3]*SPP[2] - P[22][13]*SPP[4];
+ nextP[22][5] = P[22][5] + P[22][0]*SF[2] + P[22][2]*SF[1] + P[22][3]*SF[3] - P[22][1]*SPP[0] + P[22][13]*SPP[3];
+ nextP[22][6] = P[22][6] + P[22][1]*SF[2] + P[22][3]*SF[1] + P[22][0]*SPP[0] - P[22][2]*SPP[1] - P[22][13]*SPP[5];
+ nextP[22][7] = P[22][7] + P[22][4]*dt;
+ nextP[22][8] = P[22][8] + P[22][5]*dt;
+ nextP[22][9] = P[22][9] + P[22][6]*dt;
+ nextP[22][10] = P[22][10];
+ nextP[22][11] = P[22][11];
+ nextP[22][12] = P[22][12];
+ nextP[22][13] = P[22][13];
+ nextP[22][14] = P[22][14];
+ nextP[22][15] = P[22][15];
+ nextP[22][16] = P[22][16];
+ nextP[22][17] = P[22][17];
+ nextP[22][18] = P[22][18];
+ nextP[22][19] = P[22][19];
+ nextP[22][20] = P[22][20];
+ nextP[22][21] = P[22][21];
+ nextP[22][22] = P[22][22];
+
+ for (unsigned i = 0; i < n_states; i++)
+ {
+ 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
+ // 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 <= 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];
+ }
+
+ // 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] = sq(vneSigma) + sq(velErr);
+ R_OBS[1] = R_OBS[0];
+ R_OBS[2] = sq(vdSigma) + sq(velErr);
+ R_OBS[3] = sq(posNeSigma) + sq(posErr);
+ 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)
+ {
+ // 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 = 22;
+ }
+ else
+ {
+ indexLimit = 13;
+ }
+ // 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;
+ }
+
+ // Don't update Z accel bias state unless using a height observation (GPS velocities can be biased)
+ if (obsIndex != 5) {
+ Kfusion[13] = 0;
+ }
+
+ // 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();
+
+}
+
+void AttPosEKF::FuseMagnetometer()
+{
+
+ float &q0 = magstate.q0;
+ float &q1 = magstate.q1;
+ float &q2 = magstate.q2;
+ float &q3 = magstate.q3;
+ float &magN = magstate.magN;
+ float &magE = magstate.magE;
+ float &magD = magstate.magD;
+ float &magXbias = magstate.magXbias;
+ float &magYbias = magstate.magYbias;
+ float &magZbias = magstate.magZbias;
+ unsigned &obsIndex = magstate.obsIndex;
+ Mat3f &DCM = magstate.DCM;
+ float *MagPred = &magstate.MagPred[0];
+ float &R_MAG = magstate.R_MAG;
+ float *SH_MAG = &magstate.SH_MAG[0];
+
+ float SK_MX[6];
+ float SK_MY[5];
+ float SK_MZ[6];
+ float H_MAG[n_states];
+ 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
+// 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 = 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)
+ {
+ // Copy required states to local variable names
+ q0 = statesAtMagMeasTime[0];
+ q1 = statesAtMagMeasTime[1];
+ q2 = statesAtMagMeasTime[2];
+ q3 = statesAtMagMeasTime[3];
+ magN = statesAtMagMeasTime[16];
+ magE = statesAtMagMeasTime[17];
+ magD = statesAtMagMeasTime[18];
+ magXbias = statesAtMagMeasTime[19];
+ magYbias = statesAtMagMeasTime[20];
+ magZbias = statesAtMagMeasTime[21];
+
+ // rotate predicted earth components into body axes and calculate
+ // predicted measurments
+ DCM.x.x = q0*q0 + q1*q1 - q2*q2 - q3*q3;
+ DCM.x.y = 2*(q1*q2 + q0*q3);
+ DCM.x.z = 2*(q1*q3-q0*q2);
+ DCM.y.x = 2*(q1*q2 - q0*q3);
+ DCM.y.y = q0*q0 - q1*q1 + q2*q2 - q3*q3;
+ DCM.y.z = 2*(q2*q3 + q0*q1);
+ DCM.z.x = 2*(q1*q3 + q0*q2);
+ DCM.z.y = 2*(q2*q3 - q0*q1);
+ DCM.z.z = q0*q0 - q1*q1 - q2*q2 + q3*q3;
+ MagPred[0] = DCM.x.x*magN + DCM.x.y*magE + DCM.x.z*magD + magXbias;
+ MagPred[1] = DCM.y.x*magN + DCM.y.y*magE + DCM.y.z*magD + magYbias;
+ MagPred[2] = DCM.z.x*magN + DCM.z.y*magE + DCM.z.z*magD + magZbias;
+
+ // scale magnetometer observation error with total angular rate
+ R_MAG = sq(magMeasurementSigma) + 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 < n_states; 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[16] = SH_MAG[5] - SH_MAG[4] - SH_MAG[3] + SH_MAG[6];
+ H_MAG[17] = 2*q0*q3 + 2*q1*q2;
+ H_MAG[18] = 2*q1*q3 - 2*q0*q2;
+ H_MAG[19] = 1.0f;
+
+ // Calculate Kalman gain
+ float temp = (P[19][19] + R_MAG + P[1][19]*SH_MAG[0] + P[3][19]*SH_MAG[2] - P[16][19]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) - (2*magD*q0 - 2*magE*q1 + 2*magN*q2)*(P[19][2] + P[1][2]*SH_MAG[0] + P[3][2]*SH_MAG[2] - P[16][2]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][2]*(2*q0*q3 + 2*q1*q2) - P[18][2]*(2*q0*q2 - 2*q1*q3) - P[2][2]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[19][0] + P[1][0]*SH_MAG[0] + P[3][0]*SH_MAG[2] - P[16][0]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][0]*(2*q0*q3 + 2*q1*q2) - P[18][0]*(2*q0*q2 - 2*q1*q3) - P[2][0]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[19][1] + P[1][1]*SH_MAG[0] + P[3][1]*SH_MAG[2] - P[16][1]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][1]*(2*q0*q3 + 2*q1*q2) - P[18][1]*(2*q0*q2 - 2*q1*q3) - P[2][1]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[2]*(P[19][3] + P[1][3]*SH_MAG[0] + P[3][3]*SH_MAG[2] - P[16][3]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][3]*(2*q0*q3 + 2*q1*q2) - P[18][3]*(2*q0*q2 - 2*q1*q3) - P[2][3]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6])*(P[19][16] + P[1][16]*SH_MAG[0] + P[3][16]*SH_MAG[2] - P[16][16]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][16]*(2*q0*q3 + 2*q1*q2) - P[18][16]*(2*q0*q2 - 2*q1*q3) - P[2][16]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[17][19]*(2*q0*q3 + 2*q1*q2) - P[18][19]*(2*q0*q2 - 2*q1*q3) - P[2][19]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + (2*q0*q3 + 2*q1*q2)*(P[19][17] + P[1][17]*SH_MAG[0] + P[3][17]*SH_MAG[2] - P[16][17]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][17]*(2*q0*q3 + 2*q1*q2) - P[18][17]*(2*q0*q2 - 2*q1*q3) - P[2][17]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q2 - 2*q1*q3)*(P[19][18] + P[1][18]*SH_MAG[0] + P[3][18]*SH_MAG[2] - P[16][18]*(SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6]) + P[17][18]*(2*q0*q3 + 2*q1*q2) - P[18][18]*(2*q0*q2 - 2*q1*q3) - P[2][18]*(2*magD*q0 - 2*magE*q1 + 2*magN*q2) + P[0][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[0][19]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MX[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[19][19] += 0.1f*R_MAG;
+ obsIndex = 1;
+ return;
+ }
+ SK_MX[1] = SH_MAG[3] + SH_MAG[4] - SH_MAG[5] - SH_MAG[6];
+ SK_MX[2] = 2*magD*q0 - 2*magE*q1 + 2*magN*q2;
+ SK_MX[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ 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][19] + 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][16]*SK_MX[1] + P[0][17]*SK_MX[5] - P[0][18]*SK_MX[4]);
+ Kfusion[1] = SK_MX[0]*(P[1][19] + 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][16]*SK_MX[1] + P[1][17]*SK_MX[5] - P[1][18]*SK_MX[4]);
+ Kfusion[2] = SK_MX[0]*(P[2][19] + 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][16]*SK_MX[1] + P[2][17]*SK_MX[5] - P[2][18]*SK_MX[4]);
+ Kfusion[3] = SK_MX[0]*(P[3][19] + 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][16]*SK_MX[1] + P[3][17]*SK_MX[5] - P[3][18]*SK_MX[4]);
+ Kfusion[4] = SK_MX[0]*(P[4][19] + 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][16]*SK_MX[1] + P[4][17]*SK_MX[5] - P[4][18]*SK_MX[4]);
+ Kfusion[5] = SK_MX[0]*(P[5][19] + 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][16]*SK_MX[1] + P[5][17]*SK_MX[5] - P[5][18]*SK_MX[4]);
+ Kfusion[6] = SK_MX[0]*(P[6][19] + 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][16]*SK_MX[1] + P[6][17]*SK_MX[5] - P[6][18]*SK_MX[4]);
+ Kfusion[7] = SK_MX[0]*(P[7][19] + 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][16]*SK_MX[1] + P[7][17]*SK_MX[5] - P[7][18]*SK_MX[4]);
+ Kfusion[8] = SK_MX[0]*(P[8][19] + 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][16]*SK_MX[1] + P[8][17]*SK_MX[5] - P[8][18]*SK_MX[4]);
+ Kfusion[9] = SK_MX[0]*(P[9][19] + 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][16]*SK_MX[1] + P[9][17]*SK_MX[5] - P[9][18]*SK_MX[4]);
+ Kfusion[10] = SK_MX[0]*(P[10][19] + 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][16]*SK_MX[1] + P[10][17]*SK_MX[5] - P[10][18]*SK_MX[4]);
+ Kfusion[11] = SK_MX[0]*(P[11][19] + 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][16]*SK_MX[1] + P[11][17]*SK_MX[5] - P[11][18]*SK_MX[4]);
+ 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]);
+ 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
+ {
+ // 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[16] = 2*q1*q2 - 2*q0*q3;
+ H_MAG[17] = SH_MAG[4] - SH_MAG[3] - SH_MAG[5] + SH_MAG[6];
+ H_MAG[18] = 2*q0*q1 + 2*q2*q3;
+ H_MAG[20] = 1;
+
+ // Calculate Kalman gain
+ float temp = (P[20][20] + R_MAG + P[0][20]*SH_MAG[2] + P[1][20]*SH_MAG[1] + P[2][20]*SH_MAG[0] - P[17][20]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - (2*q0*q3 - 2*q1*q2)*(P[20][16] + P[0][16]*SH_MAG[2] + P[1][16]*SH_MAG[1] + P[2][16]*SH_MAG[0] - P[17][16]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][16]*(2*q0*q3 - 2*q1*q2) + P[18][16]*(2*q0*q1 + 2*q2*q3) - P[3][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (2*q0*q1 + 2*q2*q3)*(P[20][18] + P[0][18]*SH_MAG[2] + P[1][18]*SH_MAG[1] + P[2][18]*SH_MAG[0] - P[17][18]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][18]*(2*q0*q3 - 2*q1*q2) + P[18][18]*(2*q0*q1 + 2*q2*q3) - P[3][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[20][3] + P[0][3]*SH_MAG[2] + P[1][3]*SH_MAG[1] + P[2][3]*SH_MAG[0] - P[17][3]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][3]*(2*q0*q3 - 2*q1*q2) + P[18][3]*(2*q0*q1 + 2*q2*q3) - P[3][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[16][20]*(2*q0*q3 - 2*q1*q2) + P[18][20]*(2*q0*q1 + 2*q2*q3) + SH_MAG[2]*(P[20][0] + P[0][0]*SH_MAG[2] + P[1][0]*SH_MAG[1] + P[2][0]*SH_MAG[0] - P[17][0]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][0]*(2*q0*q3 - 2*q1*q2) + P[18][0]*(2*q0*q1 + 2*q2*q3) - P[3][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[20][1] + P[0][1]*SH_MAG[2] + P[1][1]*SH_MAG[1] + P[2][1]*SH_MAG[0] - P[17][1]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][1]*(2*q0*q3 - 2*q1*q2) + P[18][1]*(2*q0*q1 + 2*q2*q3) - P[3][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[20][2] + P[0][2]*SH_MAG[2] + P[1][2]*SH_MAG[1] + P[2][2]*SH_MAG[0] - P[17][2]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][2]*(2*q0*q3 - 2*q1*q2) + P[18][2]*(2*q0*q1 + 2*q2*q3) - P[3][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6])*(P[20][17] + P[0][17]*SH_MAG[2] + P[1][17]*SH_MAG[1] + P[2][17]*SH_MAG[0] - P[17][17]*(SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6]) - P[16][17]*(2*q0*q3 - 2*q1*q2) + P[18][17]*(2*q0*q1 + 2*q2*q3) - P[3][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - P[3][20]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MY[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[20][20] += 0.1f*R_MAG;
+ obsIndex = 2;
+ return;
+ }
+ SK_MY[1] = SH_MAG[3] - SH_MAG[4] + SH_MAG[5] - SH_MAG[6];
+ SK_MY[2] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ SK_MY[3] = 2*q0*q3 - 2*q1*q2;
+ SK_MY[4] = 2*q0*q1 + 2*q2*q3;
+ Kfusion[0] = SK_MY[0]*(P[0][20] + 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][17]*SK_MY[1] - P[0][16]*SK_MY[3] + P[0][18]*SK_MY[4]);
+ Kfusion[1] = SK_MY[0]*(P[1][20] + 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][17]*SK_MY[1] - P[1][16]*SK_MY[3] + P[1][18]*SK_MY[4]);
+ Kfusion[2] = SK_MY[0]*(P[2][20] + 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][17]*SK_MY[1] - P[2][16]*SK_MY[3] + P[2][18]*SK_MY[4]);
+ Kfusion[3] = SK_MY[0]*(P[3][20] + 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][17]*SK_MY[1] - P[3][16]*SK_MY[3] + P[3][18]*SK_MY[4]);
+ Kfusion[4] = SK_MY[0]*(P[4][20] + 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][17]*SK_MY[1] - P[4][16]*SK_MY[3] + P[4][18]*SK_MY[4]);
+ Kfusion[5] = SK_MY[0]*(P[5][20] + 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][17]*SK_MY[1] - P[5][16]*SK_MY[3] + P[5][18]*SK_MY[4]);
+ Kfusion[6] = SK_MY[0]*(P[6][20] + 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][17]*SK_MY[1] - P[6][16]*SK_MY[3] + P[6][18]*SK_MY[4]);
+ Kfusion[7] = SK_MY[0]*(P[7][20] + 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][17]*SK_MY[1] - P[7][16]*SK_MY[3] + P[7][18]*SK_MY[4]);
+ Kfusion[8] = SK_MY[0]*(P[8][20] + 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][17]*SK_MY[1] - P[8][16]*SK_MY[3] + P[8][18]*SK_MY[4]);
+ Kfusion[9] = SK_MY[0]*(P[9][20] + 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][17]*SK_MY[1] - P[9][16]*SK_MY[3] + P[9][18]*SK_MY[4]);
+ Kfusion[10] = SK_MY[0]*(P[10][20] + 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][17]*SK_MY[1] - P[10][16]*SK_MY[3] + P[10][18]*SK_MY[4]);
+ Kfusion[11] = SK_MY[0]*(P[11][20] + 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][17]*SK_MY[1] - P[11][16]*SK_MY[3] + P[11][18]*SK_MY[4]);
+ 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]);
+ 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 < n_states; 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[16] = 2*q0*q2 + 2*q1*q3;
+ H_MAG[17] = 2*q2*q3 - 2*q0*q1;
+ H_MAG[18] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
+ H_MAG[21] = 1;
+
+ // Calculate Kalman gain
+ float temp = (P[21][21] + R_MAG + P[0][21]*SH_MAG[1] + P[3][21]*SH_MAG[0] + P[18][21]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) - (2*magD*q1 + 2*magE*q0 - 2*magN*q3)*(P[21][1] + P[0][1]*SH_MAG[1] + P[3][1]*SH_MAG[0] + P[18][1]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][1]*(2*q0*q2 + 2*q1*q3) - P[17][1]*(2*q0*q1 - 2*q2*q3) - P[1][1]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][1]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[7] + SH_MAG[8] - 2*magD*q2)*(P[21][2] + P[0][2]*SH_MAG[1] + P[3][2]*SH_MAG[0] + P[18][2]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][2]*(2*q0*q2 + 2*q1*q3) - P[17][2]*(2*q0*q1 - 2*q2*q3) - P[1][2]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][2]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[1]*(P[21][0] + P[0][0]*SH_MAG[1] + P[3][0]*SH_MAG[0] + P[18][0]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][0]*(2*q0*q2 + 2*q1*q3) - P[17][0]*(2*q0*q1 - 2*q2*q3) - P[1][0]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][0]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + SH_MAG[0]*(P[21][3] + P[0][3]*SH_MAG[1] + P[3][3]*SH_MAG[0] + P[18][3]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][3]*(2*q0*q2 + 2*q1*q3) - P[17][3]*(2*q0*q1 - 2*q2*q3) - P[1][3]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][3]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + (SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6])*(P[21][18] + P[0][18]*SH_MAG[1] + P[3][18]*SH_MAG[0] + P[18][18]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][18]*(2*q0*q2 + 2*q1*q3) - P[17][18]*(2*q0*q1 - 2*q2*q3) - P[1][18]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][18]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[16][21]*(2*q0*q2 + 2*q1*q3) - P[17][21]*(2*q0*q1 - 2*q2*q3) - P[1][21]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + (2*q0*q2 + 2*q1*q3)*(P[21][16] + P[0][16]*SH_MAG[1] + P[3][16]*SH_MAG[0] + P[18][16]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][16]*(2*q0*q2 + 2*q1*q3) - P[17][16]*(2*q0*q1 - 2*q2*q3) - P[1][16]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][16]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) - (2*q0*q1 - 2*q2*q3)*(P[21][17] + P[0][17]*SH_MAG[1] + P[3][17]*SH_MAG[0] + P[18][17]*(SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6]) + P[16][17]*(2*q0*q2 + 2*q1*q3) - P[17][17]*(2*q0*q1 - 2*q2*q3) - P[1][17]*(2*magD*q1 + 2*magE*q0 - 2*magN*q3) + P[2][17]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2)) + P[2][21]*(SH_MAG[7] + SH_MAG[8] - 2*magD*q2));
+ if (temp >= R_MAG) {
+ SK_MZ[0] = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the state variances and try again next time
+ P[21][21] += 0.1f*R_MAG;
+ obsIndex = 3;
+ return;
+ }
+ SK_MZ[1] = SH_MAG[3] - SH_MAG[4] - SH_MAG[5] + SH_MAG[6];
+ SK_MZ[2] = 2*magD*q1 + 2*magE*q0 - 2*magN*q3;
+ SK_MZ[3] = SH_MAG[7] + SH_MAG[8] - 2*magD*q2;
+ 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][21] + 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][18]*SK_MZ[1] + P[0][16]*SK_MZ[5] - P[0][17]*SK_MZ[4]);
+ Kfusion[1] = SK_MZ[0]*(P[1][21] + 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][18]*SK_MZ[1] + P[1][16]*SK_MZ[5] - P[1][17]*SK_MZ[4]);
+ Kfusion[2] = SK_MZ[0]*(P[2][21] + 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][18]*SK_MZ[1] + P[2][16]*SK_MZ[5] - P[2][17]*SK_MZ[4]);
+ Kfusion[3] = SK_MZ[0]*(P[3][21] + 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][18]*SK_MZ[1] + P[3][16]*SK_MZ[5] - P[3][17]*SK_MZ[4]);
+ Kfusion[4] = SK_MZ[0]*(P[4][21] + 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][18]*SK_MZ[1] + P[4][16]*SK_MZ[5] - P[4][17]*SK_MZ[4]);
+ Kfusion[5] = SK_MZ[0]*(P[5][21] + 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][18]*SK_MZ[1] + P[5][16]*SK_MZ[5] - P[5][17]*SK_MZ[4]);
+ Kfusion[6] = SK_MZ[0]*(P[6][21] + 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][18]*SK_MZ[1] + P[6][16]*SK_MZ[5] - P[6][17]*SK_MZ[4]);
+ Kfusion[7] = SK_MZ[0]*(P[7][21] + 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][18]*SK_MZ[1] + P[7][16]*SK_MZ[5] - P[7][17]*SK_MZ[4]);
+ Kfusion[8] = SK_MZ[0]*(P[8][21] + 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][18]*SK_MZ[1] + P[8][16]*SK_MZ[5] - P[8][17]*SK_MZ[4]);
+ Kfusion[9] = SK_MZ[0]*(P[9][21] + 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][18]*SK_MZ[1] + P[9][16]*SK_MZ[5] - P[9][17]*SK_MZ[4]);
+ Kfusion[10] = SK_MZ[0]*(P[10][21] + 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][18]*SK_MZ[1] + P[10][16]*SK_MZ[5] - P[10][17]*SK_MZ[4]);
+ Kfusion[11] = SK_MZ[0]*(P[11][21] + 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][18]*SK_MZ[1] + P[11][16]*SK_MZ[5] - P[11][17]*SK_MZ[4]);
+ 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]);
+ 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 <= 15; j++) KH[i][j] = 0.0f;
+ if (!onGround)
+ {
+ for (uint8_t j = 16; j <= 21; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_MAG[j];
+ }
+ }
+ else
+ {
+ for (uint8_t j = 16; j <= 21; 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 = 16; k<=21; 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;
+ float R_TAS = sq(airspeedMeasurementSigma);
+ float SH_TAS[3];
+ float SK_TAS;
+ float VtasPred;
+
+ // Copy required states to local variable names
+ vn = statesAtVtasMeasTime[4];
+ ve = statesAtVtasMeasTime[5];
+ vd = statesAtVtasMeasTime[6];
+ vwn = statesAtVtasMeasTime[14];
+ vwe = statesAtVtasMeasTime[15];
+
+ // 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[n_states];
+ for (uint8_t i = 0; i < n_states; 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[14] = -SH_TAS[2];
+ H_TAS[15] = -SH_TAS[1];
+
+ // Calculate Kalman gains
+ float temp = (R_TAS + SH_TAS[2]*(P[4][4]*SH_TAS[2] + P[5][4]*SH_TAS[1] - P[14][4]*SH_TAS[2] - P[15][4]*SH_TAS[1] + P[6][4]*vd*SH_TAS[0]) + SH_TAS[1]*(P[4][5]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[14][5]*SH_TAS[2] - P[15][5]*SH_TAS[1] + P[6][5]*vd*SH_TAS[0]) - SH_TAS[2]*(P[4][14]*SH_TAS[2] + P[5][14]*SH_TAS[1] - P[14][14]*SH_TAS[2] - P[15][14]*SH_TAS[1] + P[6][14]*vd*SH_TAS[0]) - SH_TAS[1]*(P[4][15]*SH_TAS[2] + P[5][15]*SH_TAS[1] - P[14][15]*SH_TAS[2] - P[15][15]*SH_TAS[1] + P[6][15]*vd*SH_TAS[0]) + vd*SH_TAS[0]*(P[4][6]*SH_TAS[2] + P[5][6]*SH_TAS[1] - P[14][6]*SH_TAS[2] - P[15][6]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]));
+ if (temp >= R_TAS) {
+ SK_TAS = 1.0f / temp;
+ } else {
+ // the calculation is badly conditioned, so we cannot perform fusion on this step
+ // we increase the wind state variances and try again next time
+ P[14][14] += 0.05f*R_TAS;
+ P[15][15] += 0.05f*R_TAS;
+ return;
+ }
+ Kfusion[0] = SK_TAS*(P[0][4]*SH_TAS[2] - P[0][14]*SH_TAS[2] + P[0][5]*SH_TAS[1] - P[0][15]*SH_TAS[1] + P[0][6]*vd*SH_TAS[0]);
+ Kfusion[1] = SK_TAS*(P[1][4]*SH_TAS[2] - P[1][14]*SH_TAS[2] + P[1][5]*SH_TAS[1] - P[1][15]*SH_TAS[1] + P[1][6]*vd*SH_TAS[0]);
+ Kfusion[2] = SK_TAS*(P[2][4]*SH_TAS[2] - P[2][14]*SH_TAS[2] + P[2][5]*SH_TAS[1] - P[2][15]*SH_TAS[1] + P[2][6]*vd*SH_TAS[0]);
+ Kfusion[3] = SK_TAS*(P[3][4]*SH_TAS[2] - P[3][14]*SH_TAS[2] + P[3][5]*SH_TAS[1] - P[3][15]*SH_TAS[1] + P[3][6]*vd*SH_TAS[0]);
+ Kfusion[4] = SK_TAS*(P[4][4]*SH_TAS[2] - P[4][14]*SH_TAS[2] + P[4][5]*SH_TAS[1] - P[4][15]*SH_TAS[1] + P[4][6]*vd*SH_TAS[0]);
+ Kfusion[5] = SK_TAS*(P[5][4]*SH_TAS[2] - P[5][14]*SH_TAS[2] + P[5][5]*SH_TAS[1] - P[5][15]*SH_TAS[1] + P[5][6]*vd*SH_TAS[0]);
+ Kfusion[6] = SK_TAS*(P[6][4]*SH_TAS[2] - P[6][14]*SH_TAS[2] + P[6][5]*SH_TAS[1] - P[6][15]*SH_TAS[1] + P[6][6]*vd*SH_TAS[0]);
+ Kfusion[7] = SK_TAS*(P[7][4]*SH_TAS[2] - P[7][14]*SH_TAS[2] + P[7][5]*SH_TAS[1] - P[7][15]*SH_TAS[1] + P[7][6]*vd*SH_TAS[0]);
+ Kfusion[8] = SK_TAS*(P[8][4]*SH_TAS[2] - P[8][14]*SH_TAS[2] + P[8][5]*SH_TAS[1] - P[8][15]*SH_TAS[1] + P[8][6]*vd*SH_TAS[0]);
+ Kfusion[9] = SK_TAS*(P[9][4]*SH_TAS[2] - P[9][14]*SH_TAS[2] + P[9][5]*SH_TAS[1] - P[9][15]*SH_TAS[1] + P[9][6]*vd*SH_TAS[0]);
+ Kfusion[10] = SK_TAS*(P[10][4]*SH_TAS[2] - P[10][14]*SH_TAS[2] + P[10][5]*SH_TAS[1] - P[10][15]*SH_TAS[1] + P[10][6]*vd*SH_TAS[0]);
+ Kfusion[11] = SK_TAS*(P[11][4]*SH_TAS[2] - P[11][14]*SH_TAS[2] + P[11][5]*SH_TAS[1] - P[11][15]*SH_TAS[1] + P[11][6]*vd*SH_TAS[0]);
+ 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]);
+ 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 <= 22; 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 <= 22; 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 <= 13; j++) KH[i][j] = 0.0;
+ for (uint8_t j = 14; j <= 15; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_TAS[j];
+ }
+ for (uint8_t j = 16; j <= 22; j++) KH[i][j] = 0.0;
+ }
+ for (uint8_t i = 0; i <= 22; i++)
+ {
+ for (uint8_t j = 0; j <= 22; 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 = 14; k <= 15; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ }
+ }
+ for (uint8_t i = 0; i <= 22; i++)
+ {
+ for (uint8_t j = 0; j <= 22; 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::FuseRangeFinder()
+{
+
+ // Local variables
+ float rngPred;
+ float SH_RNG[5];
+ float H_RNG[23];
+ float SK_RNG[6];
+ float cosRngTilt;
+ const float R_RNG = 0.25f; // 0.5 m2 rangefinder measurement variance
+
+ // Copy required states to local variable names
+ float q0 = statesAtRngTime[0];
+ float q1 = statesAtRngTime[1];
+ float q2 = statesAtRngTime[2];
+ float q3 = statesAtRngTime[3];
+ float pd = statesAtRngTime[9];
+ float ptd = statesAtRngTime[22];
+
+ // Need to check that our range finder tilt angle is less than 30 degrees and we are using range finder data
+ SH_RNG[4] = sin(rngFinderPitch);
+ cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cos(rngFinderPitch);
+ if (useRangeFinder && 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
+ SH_RNG[0] = SH_RNG[4]*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
+ SH_RNG[1] = pd - ptd;
+ SH_RNG[2] = 1/sq(SH_RNG[0]);
+ SH_RNG[3] = 1/SH_RNG[0];
+ for (uint8_t i = 0; i < n_states; i++) {
+ H_RNG[i] = 0.0f;
+ Kfusion[i] = 0.0f;
+ }
+ H_RNG[22] = -SH_RNG[3];
+ SK_RNG[0] = 1/(R_RNG + SH_RNG[3]*(P[9][9]*SH_RNG[3] - P[22][9]*SH_RNG[3] + P[0][9]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][9]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][9]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][9]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[3]*(P[9][22]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[0][22]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][22]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][22]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][22]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) + SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4])*(P[9][0]*SH_RNG[3] - P[22][0]*SH_RNG[3] + P[0][0]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][0]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][0]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][0]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4])*(P[9][1]*SH_RNG[3] - P[22][1]*SH_RNG[3] + P[0][1]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][1]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][1]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][1]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) - SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4])*(P[9][2]*SH_RNG[3] - P[22][2]*SH_RNG[3] + P[0][2]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][2]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][2]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][2]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])) + SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])*(P[9][3]*SH_RNG[3] - P[22][3]*SH_RNG[3] + P[0][3]*SH_RNG[1]*SH_RNG[2]*(2*q0 - 2*q2*SH_RNG[4]) - P[1][3]*SH_RNG[1]*SH_RNG[2]*(2*q1 - 2*q3*SH_RNG[4]) - P[2][3]*SH_RNG[1]*SH_RNG[2]*(2*q2 + 2*q0*SH_RNG[4]) + P[3][3]*SH_RNG[1]*SH_RNG[2]*(2*q3 + 2*q1*SH_RNG[4])));
+ SK_RNG[1] = 2*q1 - 2*q3*SH_RNG[4];
+ SK_RNG[2] = 2*q0 - 2*q2*SH_RNG[4];
+ SK_RNG[3] = 2*q3 + 2*q1*SH_RNG[4];
+ SK_RNG[4] = 2*q2 + 2*q0*SH_RNG[4];
+ SK_RNG[5] = SH_RNG[2];
+ Kfusion[22] = SK_RNG[0]*(P[22][9]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[22][0]*SH_RNG[1]*SK_RNG[2]*SK_RNG[5] - P[22][1]*SH_RNG[1]*SK_RNG[1]*SK_RNG[5] - P[22][2]*SH_RNG[1]*SK_RNG[4]*SK_RNG[5] + P[22][3]*SH_RNG[1]*SK_RNG[3]*SK_RNG[5]);
+
+ // 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)
+ {
+ // correct the state vector
+ states[22] = states[22] - Kfusion[22] * innovRng;
+
+ // correct the covariance P = (I - K*H)*P
+ P[22][22] = P[22][22] - Kfusion[22] * H_RNG[22] * P[22][22];
+ P[22][22] = ConstrainFloat(P[22][22], 0.0f, 10000.0f);
+ }
+ }
+
+}
+
+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, uint64_t msec)
+{
+ int ret = 0;
+
+ int64_t bestTimeDelta = 200;
+ unsigned bestStoreIndex = 0;
+ for (unsigned storeIndex = 0; storeIndex < data_buffer_size; storeIndex++)
+ {
+ // 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];
+ } else {
+ timeDelta = statetimeStamp[storeIndex] - msec;
+ }
+
+ if (timeDelta < bestTimeDelta)
+ {
+ bestStoreIndex = storeIndex;
+ bestTimeDelta = timeDelta;
+ }
+ }
+ if (bestTimeDelta < 200) // only output stored state if < 200 msec retrieval error
+ {
+ for (unsigned 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 (unsigned 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], double lat, double lon, float hgt, double latRef, double 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 < 6.0f));
+ if (staticMode) {
+ staticMode = (!refSet || (GPSstatus < GPS_FIX_3D));
+ }
+}
+
+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.7f);
+ P[5][5] = P[4][4];
+ P[6][6] = sq(0.7f);
+ P[7][7] = sq(15.0f);
+ P[8][8] = P[7][7];
+ P[9][9] = sq(5.0f);
+ P[10][10] = sq(0.1f*deg2rad*dtIMU);
+ 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[16][16] = sq(0.02f);
+ P[17][17] = P[16][16];
+ P[18][18] = P[16][16];
+ P[19][19] = sq(0.02f);
+ P[20][20] = P[19][19];
+ P[21][21] = P[19][19];
+ P[22][22] = sq(0.5f);
+}
+
+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);
+ } else if (val < min) {
+ ret = min;
+ ekf_debug("< min: %8.4f, val: %8.4f", min, val);
+ } else {
+ ret = val;
+ }
+
+ if (!isfinite(val)) {
+ ekf_debug("constrain: non-finite!");
+ }
+
+ return ret;
+}
+
+void AttPosEKF::ConstrainVariances()
+{
+ 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: Delta Velocity bias - m/s (Z)
+ // 14-15: Wind Vector - m/sec (North,East)
+ // 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
+ // 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)
+ // 22: Terrain offset - m
+
+ // Constrain quaternion variances
+ for (unsigned i = 0; i <= 3; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+ // Constrain velocity variances
+ for (unsigned i = 4; i <= 6; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
+ }
+
+ // Constrain position variances
+ for (unsigned i = 7; i <= 9; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e6f);
+ }
+
+ // Constrain delta angle bias variances
+ for (unsigned i = 10; i <= 12; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, sq(0.12f * dtIMU));
+ }
+
+ // Constrain delta velocity bias variance
+ P[13][13] = ConstrainFloat(P[13][13], 0.0f, sq(1.0f * dtIMU));
+
+ // Wind velocity variances
+ for (unsigned i = 14; i <= 15; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0e3f);
+ }
+
+ // Earth magnetic field variances
+ for (unsigned i = 16; i <= 18; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+ // Body magnetic field variances
+ for (unsigned i = 19; i <= 21; i++) {
+ P[i][i] = ConstrainFloat(P[i][i], 0.0f, 1.0f);
+ }
+
+ // Constrain terrain offset variance
+ P[22][22] = ConstrainFloat(P[22][22], 0.0f, 10000.0f);
+}
+
+void AttPosEKF::ConstrainStates()
+{
+ 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: Delta Velocity bias - m/s (Z)
+ // 14-15: Wind Vector - m/sec (North,East)
+ // 16-18: Earth Magnetic Field Vector - gauss (North, East, Down)
+ // 19-21: Body Magnetic Field Vector - gauss (X,Y,Z)
+ // 22: Terrain offset - m
+
+ // Constrain quaternion
+ for (unsigned i = 0; i <= 3; i++) {
+ states[i] = ConstrainFloat(states[i], -1.0f, 1.0f);
+ }
+
+ // Constrain velocities to what GPS can do for us
+ for (unsigned i = 4; i <= 6; i++) {
+ states[i] = ConstrainFloat(states[i], -5.0e2f, 5.0e2f);
+ }
+
+ // Constrain position to a reasonable vehicle range (in meters)
+ for (unsigned i = 7; i <= 8; 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 <= 12; i++) {
+ states[i] = ConstrainFloat(states[i], -0.12f * dtIMU, 0.12f * dtIMU);
+ }
+
+ // Constrain delta velocity bias
+ states[13] = ConstrainFloat(states[13], -1.0f * dtIMU, 1.0f * dtIMU);
+
+ // Wind velocity limits - assume 120 m/s max velocity
+ for (unsigned i = 14; i <= 15; i++) {
+ states[i] = ConstrainFloat(states[i], -120.0f, 120.0f);
+ }
+
+ // Earth magnetic field limits (in Gauss)
+ for (unsigned i = 16; 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 = 19; i <= 21; i++) {
+ states[i] = ConstrainFloat(states[i], -0.5f, 0.5f);
+ }
+
+ // Constrain terrain offset
+ states[22] = ConstrainFloat(states[22], -1000.0f, 1000.0f);
+
+}
+
+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 (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 err = false;
+
+ // check all integrators
+ if (!isfinite(summedDelAng.x) || !isfinite(summedDelAng.y) || !isfinite(summedDelAng.z)) {
+ err_report->statesNaN = 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;
+ 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;
+ ekf_debug("summedDelVel NaN: x: %f y: %f z: %f", (double)summedDelVel.x, (double)summedDelVel.y, (double)summedDelVel.z);
+ err = true;
+ goto out;
+ } // delta velocities
+
+ // 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;
+ ekf_debug("KH NaN");
+ goto out;
+ } // intermediate result used for covariance updates
+
+ if (!isfinite(KHP[i][j])) {
+
+ err_report->covarianceNaN = true;
+ err = true;
+ ekf_debug("KHP NaN");
+ goto out;
+ } // intermediate result used for covariance updates
+
+ if (!isfinite(P[i][j])) {
+
+ err_report->covarianceNaN = true;
+ err = true;
+ ekf_debug("P NaN");
+ } // covariance matrix
+ }
+
+ if (!isfinite(Kfusion[i])) {
+
+ err_report->kalmanGainsNaN = true;
+ ekf_debug("Kfusion NaN");
+ err = true;
+ goto out;
+ } // Kalman gains
+
+ if (!isfinite(states[i])) {
+
+ err_report->statesNaN = true;
+ ekf_debug("states NaN: i: %u val: %f", i, (double)states[i]);
+ err = true;
+ goto out;
+ } // state matrix
+ }
+
+out:
+ 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)) {
+ ekf_debug("re-initializing dynamic");
+
+ InitializeDynamic(velNED, magDeclination);
+
+ return 1;
+ }
+
+ // Reset the filter if the IMU data is too old
+ if (dtIMU > 0.3f) {
+
+ 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 = atan2f(-ay, -az);
+ initialPitch = atan2f(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;
+
+ /* normalize */
+ float norm = sqrtf(initQuat[0]*initQuat[0] + initQuat[1]*initQuat[1] + initQuat[2]*initQuat[2] + initQuat[3]*initQuat[3]);
+
+ initQuat[0] /= norm;
+ initQuat[1] /= norm;
+ initQuat[2] /= norm;
+ initQuat[3] /= norm;
+}
+
+void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination)
+{
+
+ // Fill variables with valid data
+ velNED[0] = initvelNED[0];
+ velNED[1] = initvelNED[1];
+ velNED[2] = initvelNED[2];
+ magDeclination = declination;
+
+ // 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, declination, 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;
+ 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;
+
+ magstate.q0 = initQuat[0];
+ magstate.q1 = initQuat[1];
+ magstate.q2 = initQuat[2];
+ magstate.q3 = initQuat[3];
+ magstate.magN = initMagNED.x;
+ magstate.magE = initMagNED.y;
+ magstate.magD = initMagNED.z;
+ magstate.magXbias = magBias.x;
+ magstate.magYbias = magBias.y;
+ magstate.magZbias = magBias.z;
+ magstate.R_MAG = sq(magMeasurementSigma);
+ magstate.DCM = DCM;
+
+ // 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
+ states[16] = initMagNED.x; // Magnetic Field North
+ states[17] = initMagNED.y; // Magnetic Field East
+ states[18] = initMagNED.z; // Magnetic Field Down
+ states[19] = magBias.x; // Magnetic Field Bias X
+ states[20] = magBias.y; // Magnetic Field Bias Y
+ states[21] = magBias.z; // Magnetic Field Bias Z
+ states[22] = 0.0f; // terrain height
+
+ ResetVelocity();
+ ResetPosition();
+ ResetHeight();
+
+ statesInitialised = true;
+
+ // initialise the covariance matrix
+ CovarianceInit();
+
+ //Define Earth rotation vector in the NED navigation frame
+ calcEarthRateNED(earthRateNED, latRef);
+
+}
+
+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;
+ refSet = true;
+
+ // we are at reference altitude, so measurement must be zero
+ hgtMea = 0.0f;
+
+ // the baro offset must be this difference now
+ baroHgtOffset = baroHgt - referenceHgt;
+
+ memset(&last_ekf_error, 0, sizeof(last_ekf_error));
+
+ InitializeDynamic(initvelNED, declination);
+}
+
+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++) {
+ 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
+ }
+
+ correctedDelAng.zero();
+ summedDelAng.zero();
+ summedDelVel.zero();
+
+ dAngIMU.zero();
+ dVelIMU.zero();
+
+ 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(&magstate, 0, sizeof(magstate));
+ magstate.q0 = 1.0f;
+ magstate.DCM.identity();
+
+ 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/fw_att_pos_estimator/estimator.h b/src/modules/ekf_att_pos_estimator/estimator.h
index e62f1a98a..e821089f2 100644
--- a/src/modules/fw_att_pos_estimator/estimator.h
+++ b/src/modules/ekf_att_pos_estimator/estimator.h
@@ -20,7 +20,7 @@ public:
float z;
float length(void) const;
- Vector3f zero(void) const;
+ void zero(void);
};
class Mat3f
@@ -33,6 +33,7 @@ public:
Mat3f();
+ void identity();
Mat3f transpose(void) const;
};
@@ -45,14 +46,9 @@ Vector3f operator*(Vector3f vecIn1, float sclIn1);
void swap_var(float &d1, float &d2);
-const unsigned int n_states = 21;
+const unsigned int n_states = 23;
const unsigned int data_buffer_size = 50;
-const float covTimeStepMax = 0.07f; // maximum time allowed between covariance predictions
-const float covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
-
-// extern bool staticMode;
-
enum GPS_FIX {
GPS_FIX_NOFIX = 0,
GPS_FIX_2D = 2,
@@ -82,6 +78,88 @@ 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;
+ }
+
+ struct {
+ unsigned obsIndex;
+ float MagPred[3];
+ float SH_MAG[9];
+ float q0;
+ float q1;
+ float q2;
+ float q3;
+ float magN;
+ float magE;
+ float magD;
+ float magXbias;
+ float magYbias;
+ float magZbias;
+ float R_MAG;
+ Mat3f DCM;
+ } magstate;
+
+
// 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
@@ -96,6 +174,7 @@ public:
float statesAtHgtTime[n_states]; // States at the effective measurement time for the hgtMea measurement
float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
+ float statesAtRngTime[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)
@@ -104,6 +183,10 @@ 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)
+
+ Mat3f Tbn; // transformation matrix from body to NED coordinates
+ Mat3f Tnb; // transformation amtrix from NED to body coordinates
+
Vector3f accel; // acceleration vector in XYZ body axes measured by the IMU (m/s^2)
Vector3f dVelIMU;
Vector3f dAngIMU;
@@ -115,26 +198,30 @@ public:
float velNED[3]; // North, East, Down velocity obs (m/s)
float posNE[2]; // North, East position obs (m)
float hgtMea; // measured height (m)
+ float baroHgtOffset; ///< the baro (weather) offset from normalized altitude
+ float rngMea; // Ground distance
float posNED[3]; // North, East Down position (m)
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 innovRng; ///< Range finder innovation
float varInnovVtas; // innovation variance output
float VtasMeas; // true airspeed measurement (m/s)
- float latRef; // WGS-84 latitude of reference point (rad)
- float lonRef; // WGS-84 longitude of reference point (rad)
+ float magDeclination; ///< magnetic declination
+ double latRef; // WGS-84 latitude of reference point (rad)
+ double lonRef; // WGS-84 longitude of reference point (rad)
float hgtRef; // WGS-84 height of reference point (m)
+ bool refSet; ///< flag to indicate if the reference position has been set
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
- float EAS2TAS; // ratio f true to equivalent airspeed
+ 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;
- float gpsLat;
- float gpsLon;
+ double gpsLat;
+ double gpsLon;
float gpsHgt;
uint8_t GPSstatus;
@@ -148,11 +235,13 @@ public:
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 fuseRngData; ///< true when range data is 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
+ bool useRangeFinder; ///< true when rangefinder is being used
struct ekf_status_report current_ekf_state;
struct ekf_status_report last_ekf_error;
@@ -172,6 +261,10 @@ void FuseMagnetometer();
void FuseAirspeed();
+void FuseRangeFinder();
+
+void FuseOpticalFlow();
+
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);
@@ -192,7 +285,7 @@ void StoreStates(uint64_t timestamp_ms);
* time-wise where valid states were updated and invalid remained at the old
* value.
*/
-int RecallStates(float statesForFusion[n_states], uint64_t msec);
+int RecallStates(float *statesForFusion, uint64_t msec);
void ResetStoredStates();
@@ -206,7 +299,7 @@ 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 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);
@@ -218,7 +311,7 @@ void OnGroundCheck();
void CovarianceInit();
-void InitialiseFilter(float (&initvelNED)[3]);
+void InitialiseFilter(float (&initvelNED)[3], double referenceLat, double referenceLon, float referenceHgt, float declination);
float ConstrainFloat(float val, float min, float max);
@@ -243,7 +336,7 @@ 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]);
+void InitializeDynamic(float (&initvelNED)[3], float declination);
protected:
@@ -251,7 +344,7 @@ bool FilterHealthy();
void ResetHeight(void);
-void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float *initQuat);
+void AttitudeInit(float ax, float ay, float az, float mx, float my, float mz, float declination, float *initQuat);
};
diff --git a/src/modules/fw_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk
index c992959e0..6fefec2c2 100644
--- a/src/modules/fw_att_pos_estimator/module.mk
+++ b/src/modules/ekf_att_pos_estimator/module.mk
@@ -32,11 +32,11 @@
############################################################################
#
-# Main Attitude and Position Estimator for Fixed Wing Aircraft
+# Main EKF Attitude and Position Estimator
#
-MODULE_COMMAND = fw_att_pos_estimator
+MODULE_COMMAND = ekf_att_pos_estimator
-SRCS = fw_att_pos_estimator_main.cpp \
- fw_att_pos_estimator_params.c \
+SRCS = ekf_att_pos_estimator_main.cpp \
+ ekf_att_pos_estimator_params.c \
estimator.cpp
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c b/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
deleted file mode 100644
index 2aeca3a98..000000000
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_att.c
+++ /dev/null
@@ -1,169 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * 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 fixedwing_att_control_rate.c
- * Implementation of a fixed wing attitude controller.
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <math.h>
-#include <poll.h>
-#include <time.h>
-#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-#include <uORB/uORB.h>
-
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <systemlib/param/param.h>
-#include <systemlib/pid/pid.h>
-#include <systemlib/geo/geo.h>
-#include <systemlib/systemlib.h>
-
-#include "fixedwing_att_control_att.h"
-
-
-struct fw_att_control_params {
- float roll_p;
- float rollrate_lim;
- float pitch_p;
- float pitchrate_lim;
- float yawrate_lim;
- float pitch_roll_compensation_p;
-};
-
-struct fw_pos_control_param_handles {
- param_t roll_p;
- param_t rollrate_lim;
- param_t pitch_p;
- param_t pitchrate_lim;
- param_t yawrate_lim;
- param_t pitch_roll_compensation_p;
-};
-
-
-
-/* Internal Prototypes */
-static int parameters_init(struct fw_pos_control_param_handles *h);
-static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p);
-
-static int parameters_init(struct fw_pos_control_param_handles *h)
-{
- /* PID parameters */
- h->roll_p = param_find("FW_ROLL_P");
- h->rollrate_lim = param_find("FW_ROLLR_LIM");
- h->pitch_p = param_find("FW_PITCH_P");
- h->pitchrate_lim = param_find("FW_PITCHR_LIM");
- h->yawrate_lim = param_find("FW_YAWR_LIM");
- h->pitch_roll_compensation_p = param_find("FW_PITCH_RCOMP");
-
- return OK;
-}
-
-static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_att_control_params *p)
-{
- param_get(h->roll_p, &(p->roll_p));
- param_get(h->rollrate_lim, &(p->rollrate_lim));
- param_get(h->pitch_p, &(p->pitch_p));
- param_get(h->pitchrate_lim, &(p->pitchrate_lim));
- param_get(h->yawrate_lim, &(p->yawrate_lim));
- param_get(h->pitch_roll_compensation_p, &(p->pitch_roll_compensation_p));
-
- return OK;
-}
-
-int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att,
- const float speed_body[],
- struct vehicle_rates_setpoint_s *rates_sp)
-{
- static int counter = 0;
- static bool initialized = false;
-
- static struct fw_att_control_params p;
- static struct fw_pos_control_param_handles h;
-
- static PID_t roll_controller;
- static PID_t pitch_controller;
-
-
- if (!initialized) {
- parameters_init(&h);
- parameters_update(&h, &p);
- pid_init(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim, PID_MODE_DERIVATIV_NONE, 0.0f); //P Controller
- pid_init(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim, PID_MODE_DERIVATIV_NONE, 0.0f); //P Controller
- initialized = true;
- }
-
- /* load new parameters with lower rate */
- if (counter % 100 == 0) {
- /* update parameters from storage */
- parameters_update(&h, &p);
- pid_set_parameters(&roll_controller, p.roll_p, 0, 0, 0, p.rollrate_lim);
- pid_set_parameters(&pitch_controller, p.pitch_p, 0, 0, 0, p.pitchrate_lim);
- }
-
- /* Roll (P) */
- rates_sp->roll = pid_calculate(&roll_controller, att_sp->roll_body, att->roll, 0, 0);
-
-
- /* Pitch (P) */
-
- /* compensate feedforward for loss of lift due to non-horizontal angle of wing */
- float pitch_sp_rollcompensation = p.pitch_roll_compensation_p * fabsf(sinf(att_sp->roll_body));
- /* set pitch plus feedforward roll compensation */
- rates_sp->pitch = pid_calculate(&pitch_controller,
- att_sp->pitch_body + pitch_sp_rollcompensation,
- att->pitch, 0, 0);
-
- /* Yaw (from coordinated turn constraint or lateral force) */
- rates_sp->yaw = (att->rollspeed * rates_sp->roll + 9.81f * sinf(att->roll) * cosf(att->pitch) + speed_body[0] * rates_sp->pitch * sinf(att->roll))
- / (speed_body[0] * cosf(att->roll) * cosf(att->pitch) + speed_body[2] * sinf(att->pitch));
-
-// printf("rates_sp->yaw %.4f \n", (double)rates_sp->yaw);
-
- counter++;
-
- return 0;
-}
-
-
-
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_att.h b/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
deleted file mode 100644
index 600e35b89..000000000
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_att.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * 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 Fixed Wing Attitude Control */
-
-#ifndef FIXEDWING_ATT_CONTROL_ATT_H_
-#define FIXEDWING_ATT_CONTROL_ATT_H_
-
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_global_position.h>
-
-int fixedwing_att_control_attitude(const struct vehicle_attitude_setpoint_s *att_sp,
- const struct vehicle_attitude_s *att,
- const float speed_body[],
- struct vehicle_rates_setpoint_s *rates_sp);
-
-#endif /* FIXEDWING_ATT_CONTROL_ATT_H_ */
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c b/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
deleted file mode 100644
index b6b4546c2..000000000
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_main.c
+++ /dev/null
@@ -1,367 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Doug Weibel <douglas.weibel@colorado.edu>
- *
- * 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 fixedwing_att_control.c
- * Implementation of a fixed wing attitude controller.
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <math.h>
-#include <poll.h>
-#include <time.h>
-#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_control_mode.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/debug_key_value.h>
-#include <systemlib/param/param.h>
-#include <systemlib/pid/pid.h>
-#include <systemlib/geo/geo.h>
-#include <systemlib/perf_counter.h>
-#include <systemlib/systemlib.h>
-
-#include "fixedwing_att_control_rate.h"
-#include "fixedwing_att_control_att.h"
-
-/* Prototypes */
-/**
- * Deamon management function.
- */
-__EXPORT int fixedwing_att_control_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int fixedwing_att_control_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-/* Variables */
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-/* Main Thread */
-int fixedwing_att_control_thread_main(int argc, char *argv[])
-{
- /* read arguments */
- bool verbose = false;
-
- for (int i = 1; i < argc; i++) {
- if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) {
- verbose = true;
- }
- }
-
- /* welcome user */
- printf("[fixedwing att control] started\n");
-
- /* declare and safely initialize all structs */
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- struct vehicle_attitude_setpoint_s att_sp;
- memset(&att_sp, 0, sizeof(att_sp));
- struct vehicle_rates_setpoint_s rates_sp;
- memset(&rates_sp, 0, sizeof(rates_sp));
- struct vehicle_global_position_s global_pos;
- memset(&global_pos, 0, sizeof(global_pos));
- struct manual_control_setpoint_s manual_sp;
- memset(&manual_sp, 0, sizeof(manual_sp));
- struct vehicle_control_mode_s control_mode;
- memset(&control_mode, 0, sizeof(control_mode));
- struct vehicle_status_s vstatus;
- memset(&vstatus, 0, sizeof(vstatus));
-
- /* output structs */
- struct actuator_controls_s actuators;
- memset(&actuators, 0, sizeof(actuators));
-
-
- /* publish actuator controls */
- for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) {
- actuators.control[i] = 0.0f;
- }
-
- orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators);
- orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp);
-
- /* subscribe */
- int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
- int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
-
- /* Setup of loop */
- float gyro[3] = {0.0f, 0.0f, 0.0f};
- float speed_body[3] = {0.0f, 0.0f, 0.0f};
- struct pollfd fds = { .fd = att_sub, .events = POLLIN };
-
- while (!thread_should_exit) {
- /* wait for a sensor update, check for exit condition every 500 ms */
- poll(&fds, 1, 500);
-
- /* Check if there is a new position measurement or attitude setpoint */
- bool pos_updated;
- orb_check(global_pos_sub, &pos_updated);
- bool att_sp_updated;
- orb_check(att_sp_sub, &att_sp_updated);
-
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
-
- if (att_sp_updated)
- orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
-
- if (pos_updated) {
- orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
-
- if (att.R_valid) {
- speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz;
- speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz;
- speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz;
-
- } else {
- speed_body[0] = 0;
- speed_body[1] = 0;
- speed_body[2] = 0;
-
- printf("FW ATT CONTROL: Did not get a valid R\n");
- }
- }
-
- orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
- orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
-
- gyro[0] = att.rollspeed;
- gyro[1] = att.pitchspeed;
- gyro[2] = att.yawspeed;
-
- /* set manual setpoints if required */
- if (control_mode.flag_control_manual_enabled) {
- if (control_mode.flag_control_attitude_enabled) {
-
- /* if the RC signal is lost, try to stay level and go slowly back down to ground */
- if (vstatus.rc_signal_lost) {
-
- /* put plane into loiter */
- att_sp.roll_body = 0.3f;
- att_sp.pitch_body = 0.0f;
-
- /* limit throttle to 60 % of last value if sane */
- if (isfinite(manual_sp.throttle) &&
- (manual_sp.throttle >= 0.0f) &&
- (manual_sp.throttle <= 1.0f)) {
- att_sp.thrust = 0.6f * manual_sp.throttle;
-
- } else {
- att_sp.thrust = 0.0f;
- }
-
- att_sp.yaw_body = 0;
-
- // XXX disable yaw control, loiter
-
- } else {
-
- att_sp.roll_body = manual_sp.roll;
- att_sp.pitch_body = manual_sp.pitch;
- att_sp.yaw_body = 0;
- att_sp.thrust = manual_sp.throttle;
- }
-
- att_sp.timestamp = hrt_absolute_time();
-
- /* pass through flaps */
- if (isfinite(manual_sp.flaps)) {
- actuators.control[4] = manual_sp.flaps;
-
- } else {
- actuators.control[4] = 0.0f;
- }
-
- } else {
- /* directly pass through values */
- actuators.control[0] = manual_sp.roll;
- /* positive pitch means negative actuator -> pull up */
- actuators.control[1] = manual_sp.pitch;
- actuators.control[2] = manual_sp.yaw;
- actuators.control[3] = manual_sp.throttle;
-
- if (isfinite(manual_sp.flaps)) {
- actuators.control[4] = manual_sp.flaps;
-
- } else {
- actuators.control[4] = 0.0f;
- }
- }
- }
-
- /* execute attitude control if requested */
- if (control_mode.flag_control_attitude_enabled) {
- /* attitude control */
- fixedwing_att_control_attitude(&att_sp, &att, speed_body, &rates_sp);
-
- /* angular rate control */
- fixedwing_att_control_rates(&rates_sp, gyro, &actuators);
-
- /* pass through throttle */
- actuators.control[3] = att_sp.thrust;
-
- /* set flaps to zero */
- actuators.control[4] = 0.0f;
-
- }
-
- /* publish rates */
- orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
-
- /* sanity check and publish actuator outputs */
- if (isfinite(actuators.control[0]) &&
- isfinite(actuators.control[1]) &&
- isfinite(actuators.control[2]) &&
- isfinite(actuators.control[3])) {
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
- }
- }
-
- printf("[fixedwing_att_control] exiting, stopping all motors.\n");
- thread_running = false;
-
- /* kill all outputs */
- for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++)
- actuators.control[i] = 0.0f;
-
- orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
-
-
-
- close(att_sub);
- close(actuator_pub);
- close(rates_pub);
-
- fflush(stdout);
- exit(0);
-
- return 0;
-
-}
-
-/* Startup Functions */
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- fprintf(stderr, "usage: fixedwing_att_control {start|stop|status}\n\n");
- exit(1);
-}
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int fixedwing_att_control_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("fixedwing_att_control already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn_cmd("fixedwing_att_control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 20,
- 2048,
- fixedwing_att_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- thread_running = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- printf("\tfixedwing_att_control is running\n");
-
- } else {
- printf("\tfixedwing_att_control not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-
-
diff --git a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c b/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
deleted file mode 100644
index cdab39edc..000000000
--- a/src/modules/fixedwing_att_control/fixedwing_att_control_rate.c
+++ /dev/null
@@ -1,211 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * 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 fixedwing_att_control_rate.c
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
- *
- * Implementation of a fixed wing attitude controller.
- *
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <math.h>
-#include <poll.h>
-#include <time.h>
-#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-#include <uORB/uORB.h>
-
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <systemlib/param/param.h>
-#include <systemlib/pid/pid.h>
-#include <systemlib/geo/geo.h>
-#include <systemlib/systemlib.h>
-
-#include "fixedwing_att_control_rate.h"
-
-/*
- * Controller parameters, accessible via MAVLink
- *
- */
-// Roll control parameters
-PARAM_DEFINE_FLOAT(FW_ROLLR_P, 0.9f);
-PARAM_DEFINE_FLOAT(FW_ROLLR_I, 0.2f);
-PARAM_DEFINE_FLOAT(FW_ROLLR_AWU, 0.9f);
-PARAM_DEFINE_FLOAT(FW_ROLLR_LIM, 0.7f); // Roll rate limit in radians/sec, applies to the roll controller
-PARAM_DEFINE_FLOAT(FW_ROLL_P, 4.0f);
-PARAM_DEFINE_FLOAT(FW_PITCH_RCOMP, 0.1f);
-
-//Pitch control parameters
-PARAM_DEFINE_FLOAT(FW_PITCHR_P, 0.8f);
-PARAM_DEFINE_FLOAT(FW_PITCHR_I, 0.2f);
-PARAM_DEFINE_FLOAT(FW_PITCHR_AWU, 0.8f);
-PARAM_DEFINE_FLOAT(FW_PITCHR_LIM, 0.35f); // Pitch rate limit in radians/sec, applies to the pitch controller
-PARAM_DEFINE_FLOAT(FW_PITCH_P, 8.0f);
-
-//Yaw control parameters //XXX TODO this is copy paste, asign correct values
-PARAM_DEFINE_FLOAT(FW_YAWR_P, 0.3f);
-PARAM_DEFINE_FLOAT(FW_YAWR_I, 0.0f);
-PARAM_DEFINE_FLOAT(FW_YAWR_AWU, 0.0f);
-PARAM_DEFINE_FLOAT(FW_YAWR_LIM, 0.35f); // Yaw rate limit in radians/sec
-
-/* feedforward compensation */
-PARAM_DEFINE_FLOAT(FW_PITCH_THR_P, 0.1f); /**< throttle to pitch coupling feedforward */
-
-struct fw_rate_control_params {
- float rollrate_p;
- float rollrate_i;
- float rollrate_awu;
- float pitchrate_p;
- float pitchrate_i;
- float pitchrate_awu;
- float yawrate_p;
- float yawrate_i;
- float yawrate_awu;
- float pitch_thr_ff;
-};
-
-struct fw_rate_control_param_handles {
- param_t rollrate_p;
- param_t rollrate_i;
- param_t rollrate_awu;
- param_t pitchrate_p;
- param_t pitchrate_i;
- param_t pitchrate_awu;
- param_t yawrate_p;
- param_t yawrate_i;
- param_t yawrate_awu;
- param_t pitch_thr_ff;
-};
-
-
-
-/* Internal Prototypes */
-static int parameters_init(struct fw_rate_control_param_handles *h);
-static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p);
-
-static int parameters_init(struct fw_rate_control_param_handles *h)
-{
- /* PID parameters */
- h->rollrate_p = param_find("FW_ROLLR_P"); //TODO define rate params for fixed wing
- h->rollrate_i = param_find("FW_ROLLR_I");
- h->rollrate_awu = param_find("FW_ROLLR_AWU");
-
- h->pitchrate_p = param_find("FW_PITCHR_P");
- h->pitchrate_i = param_find("FW_PITCHR_I");
- h->pitchrate_awu = param_find("FW_PITCHR_AWU");
-
- h->yawrate_p = param_find("FW_YAWR_P");
- h->yawrate_i = param_find("FW_YAWR_I");
- h->yawrate_awu = param_find("FW_YAWR_AWU");
- h->pitch_thr_ff = param_find("FW_PITCH_THR_P");
-
- return OK;
-}
-
-static int parameters_update(const struct fw_rate_control_param_handles *h, struct fw_rate_control_params *p)
-{
- param_get(h->rollrate_p, &(p->rollrate_p));
- param_get(h->rollrate_i, &(p->rollrate_i));
- param_get(h->rollrate_awu, &(p->rollrate_awu));
- param_get(h->pitchrate_p, &(p->pitchrate_p));
- param_get(h->pitchrate_i, &(p->pitchrate_i));
- param_get(h->pitchrate_awu, &(p->pitchrate_awu));
- param_get(h->yawrate_p, &(p->yawrate_p));
- param_get(h->yawrate_i, &(p->yawrate_i));
- param_get(h->yawrate_awu, &(p->yawrate_awu));
- param_get(h->pitch_thr_ff, &(p->pitch_thr_ff));
-
- return OK;
-}
-
-int fixedwing_att_control_rates(const struct vehicle_rates_setpoint_s *rate_sp,
- const float rates[],
- struct actuator_controls_s *actuators)
-{
- static int counter = 0;
- static bool initialized = false;
-
- static struct fw_rate_control_params p;
- static struct fw_rate_control_param_handles h;
-
- static PID_t roll_rate_controller;
- static PID_t pitch_rate_controller;
- static PID_t yaw_rate_controller;
-
- static uint64_t last_run = 0;
- const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
-
- if (!initialized) {
- parameters_init(&h);
- parameters_update(&h, &p);
- pid_init(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the controller layout is with a PI rate controller
- pid_init(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
- pid_init(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1, PID_MODE_DERIVATIV_NONE, 0.0f); // set D part to 0 because the contpitcher layout is with a PI rate contpitcher
- initialized = true;
- }
-
- /* load new parameters with lower rate */
- if (counter % 100 == 0) {
- /* update parameters from storage */
- parameters_update(&h, &p);
- pid_set_parameters(&roll_rate_controller, p.rollrate_p, p.rollrate_i, 0, p.rollrate_awu, 1);
- pid_set_parameters(&pitch_rate_controller, p.pitchrate_p, p.pitchrate_i, 0, p.pitchrate_awu, 1);
- pid_set_parameters(&yaw_rate_controller, p.yawrate_p, p.yawrate_i, 0, p.yawrate_awu, 1);
- }
-
-
- /* roll rate (PI) */
- actuators->control[0] = pid_calculate(&roll_rate_controller, rate_sp->roll, rates[0], 0.0f, deltaT);
- /* pitch rate (PI) */
- actuators->control[1] = -pid_calculate(&pitch_rate_controller, rate_sp->pitch, rates[1], 0.0f, deltaT);
- /* yaw rate (PI) */
- actuators->control[2] = pid_calculate(&yaw_rate_controller, rate_sp->yaw, rates[2], 0.0f, deltaT);
-
- counter++;
-
- return 0;
-}
-
-
-
diff --git a/src/modules/fixedwing_att_control/module.mk b/src/modules/fixedwing_att_control/module.mk
deleted file mode 100644
index fd1a8724a..000000000
--- a/src/modules/fixedwing_att_control/module.mk
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Fixedwing Attitude Control application
-#
-
-MODULE_COMMAND = fixedwing_att_control
-
-SRCS = fixedwing_att_control_main.c \
- fixedwing_att_control_att.c \
- fixedwing_att_control_rate.c
diff --git a/src/modules/fixedwing_backside/fixedwing.cpp b/src/modules/fixedwing_backside/fixedwing.cpp
index cfae07275..bbb39f20f 100644
--- a/src/modules/fixedwing_backside/fixedwing.cpp
+++ b/src/modules/fixedwing_backside/fixedwing.cpp
@@ -229,8 +229,8 @@ void BlockMultiModeBacksideAutopilot::update()
_actuators.control[CH_RDR] = _manual.yaw;
_actuators.control[CH_THR] = _manual.throttle;
- } else if (_status.main_state == MAIN_STATE_SEATBELT ||
- _status.main_state == MAIN_STATE_EASY /* TODO, implement easy */) {
+ } else if (_status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL /* TODO, implement pos control */) {
// calculate velocity, XXX should be airspeed, but using ground speed for now
// for the purpose of control we will limit the velocity feedback between
diff --git a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c b/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
deleted file mode 100644
index 888dd0942..000000000
--- a/src/modules/fixedwing_pos_control/fixedwing_pos_control_main.c
+++ /dev/null
@@ -1,479 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
- * @author Doug Weibel <douglas.weibel@colorado.edu>
- *
- * 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 fixedwing_pos_control.c
- * Implementation of a fixed wing attitude controller.
- */
-
-#include <nuttx/config.h>
-#include <stdio.h>
-#include <stdlib.h>
-#include <string.h>
-#include <unistd.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <math.h>
-#include <poll.h>
-#include <time.h>
-#include <drivers/drv_hrt.h>
-#include <arch/board/board.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_global_position_setpoint.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/manual_control_setpoint.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/vehicle_rates_setpoint.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/parameter_update.h>
-#include <systemlib/param/param.h>
-#include <systemlib/pid/pid.h>
-#include <systemlib/geo/geo.h>
-#include <systemlib/perf_counter.h>
-#include <systemlib/systemlib.h>
-
-/*
- * Controller parameters, accessible via MAVLink
- *
- */
-PARAM_DEFINE_FLOAT(FW_HEAD_P, 0.1f);
-PARAM_DEFINE_FLOAT(FW_HEADR_I, 0.1f);
-PARAM_DEFINE_FLOAT(FW_HEADR_LIM, 1.5f); //TODO: think about reasonable value
-PARAM_DEFINE_FLOAT(FW_XTRACK_P, 0.01745f); // Radians per meter off track
-PARAM_DEFINE_FLOAT(FW_ALT_P, 0.1f);
-PARAM_DEFINE_FLOAT(FW_ROLL_LIM, 0.7f); // Roll angle limit in radians
-PARAM_DEFINE_FLOAT(FW_HEADR_P, 0.1f);
-PARAM_DEFINE_FLOAT(FW_PITCH_LIM, 0.35f); /**< Pitch angle limit in radians per second */
-
-struct fw_pos_control_params {
- float heading_p;
- float headingr_p;
- float headingr_i;
- float headingr_lim;
- float xtrack_p;
- float altitude_p;
- float roll_lim;
- float pitch_lim;
-};
-
-struct fw_pos_control_param_handles {
- param_t heading_p;
- param_t headingr_p;
- param_t headingr_i;
- param_t headingr_lim;
- param_t xtrack_p;
- param_t altitude_p;
- param_t roll_lim;
- param_t pitch_lim;
-};
-
-
-struct planned_path_segments_s {
- bool segment_type;
- double start_lat; // Start of line or center of arc
- double start_lon;
- double end_lat;
- double end_lon;
- float radius; // Radius of arc
- float arc_start_bearing; // Bearing from center to start of arc
- float arc_sweep; // Angle (radians) swept out by arc around center.
- // Positive for clockwise, negative for counter-clockwise
-};
-
-
-/* Prototypes */
-/* Internal Prototypes */
-static int parameters_init(struct fw_pos_control_param_handles *h);
-static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p);
-
-/**
- * Deamon management function.
- */
-__EXPORT int fixedwing_pos_control_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int fixedwing_pos_control_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-/* Variables */
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-
-/**
- * Parameter management
- */
-static int parameters_init(struct fw_pos_control_param_handles *h)
-{
- /* PID parameters */
- h->heading_p = param_find("FW_HEAD_P");
- h->headingr_p = param_find("FW_HEADR_P");
- h->headingr_i = param_find("FW_HEADR_I");
- h->headingr_lim = param_find("FW_HEADR_LIM");
- h->xtrack_p = param_find("FW_XTRACK_P");
- h->altitude_p = param_find("FW_ALT_P");
- h->roll_lim = param_find("FW_ROLL_LIM");
- h->pitch_lim = param_find("FW_PITCH_LIM");
-
- return OK;
-}
-
-static int parameters_update(const struct fw_pos_control_param_handles *h, struct fw_pos_control_params *p)
-{
- param_get(h->heading_p, &(p->heading_p));
- param_get(h->headingr_p, &(p->headingr_p));
- param_get(h->headingr_i, &(p->headingr_i));
- param_get(h->headingr_lim, &(p->headingr_lim));
- param_get(h->xtrack_p, &(p->xtrack_p));
- param_get(h->altitude_p, &(p->altitude_p));
- param_get(h->roll_lim, &(p->roll_lim));
- param_get(h->pitch_lim, &(p->pitch_lim));
-
- return OK;
-}
-
-
-/* Main Thread */
-int fixedwing_pos_control_thread_main(int argc, char *argv[])
-{
- /* read arguments */
- bool verbose = false;
-
- for (int i = 1; i < argc; i++) {
- if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) {
- verbose = true;
- }
- }
-
- /* welcome user */
- printf("[fixedwing pos control] started\n");
-
- /* declare and safely initialize all structs */
- struct vehicle_global_position_s global_pos;
- memset(&global_pos, 0, sizeof(global_pos));
- struct vehicle_global_position_s start_pos; // Temporary variable, replace with
- memset(&start_pos, 0, sizeof(start_pos)); // previous waypoint when available
- struct vehicle_global_position_setpoint_s global_setpoint;
- memset(&global_setpoint, 0, sizeof(global_setpoint));
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- struct crosstrack_error_s xtrack_err;
- memset(&xtrack_err, 0, sizeof(xtrack_err));
- struct parameter_update_s param_update;
- memset(&param_update, 0, sizeof(param_update));
-
- /* output structs */
- struct vehicle_attitude_setpoint_s attitude_setpoint;
- memset(&attitude_setpoint, 0, sizeof(attitude_setpoint));
-
- /* publish attitude setpoint */
- attitude_setpoint.roll_body = 0.0f;
- attitude_setpoint.pitch_body = 0.0f;
- attitude_setpoint.yaw_body = 0.0f;
- attitude_setpoint.thrust = 0.0f;
- orb_advert_t attitude_setpoint_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &attitude_setpoint);
-
- /* subscribe */
- int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- int global_setpoint_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
- int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int param_sub = orb_subscribe(ORB_ID(parameter_update));
-
- /* Setup of loop */
- struct pollfd fds[2] = {
- { .fd = param_sub, .events = POLLIN },
- { .fd = att_sub, .events = POLLIN }
- };
- bool global_sp_updated_set_once = false;
-
- float psi_track = 0.0f;
-
- int counter = 0;
-
- struct fw_pos_control_params p;
- struct fw_pos_control_param_handles h;
-
- PID_t heading_controller;
- PID_t heading_rate_controller;
- PID_t offtrack_controller;
- PID_t altitude_controller;
-
- parameters_init(&h);
- parameters_update(&h, &p);
- pid_init(&heading_controller, p.heading_p, 0.0f, 0.0f, 0.0f, 10000.0f, PID_MODE_DERIVATIV_NONE, 0.0f); //arbitrary high limit
- pid_init(&heading_rate_controller, p.headingr_p, p.headingr_i, 0.0f, 0.0f, p.roll_lim, PID_MODE_DERIVATIV_NONE, 0.0f);
- pid_init(&altitude_controller, p.altitude_p, 0.0f, 0.0f, 0.0f, p.pitch_lim, PID_MODE_DERIVATIV_NONE, 0.0f);
- pid_init(&offtrack_controller, p.xtrack_p, 0.0f, 0.0f, 0.0f , 60.0f * M_DEG_TO_RAD, PID_MODE_DERIVATIV_NONE, 0.0f); //TODO: remove hardcoded value
-
- /* error and performance monitoring */
- perf_counter_t fw_interval_perf = perf_alloc(PC_INTERVAL, "fixedwing_pos_control_interval");
- perf_counter_t fw_err_perf = perf_alloc(PC_COUNT, "fixedwing_pos_control_err");
-
- while (!thread_should_exit) {
- /* wait for a sensor update, check for exit condition every 500 ms */
- int ret = poll(fds, 2, 500);
-
- if (ret < 0) {
- /* poll error, count it in perf */
- perf_count(fw_err_perf);
-
- } else if (ret == 0) {
- /* no return value, ignore */
- } else {
-
- /* only update parameters if they changed */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), param_sub, &update);
-
- /* update parameters from storage */
- parameters_update(&h, &p);
- pid_set_parameters(&heading_controller, p.heading_p, 0, 0, 0, 10000.0f); //arbitrary high limit
- pid_set_parameters(&heading_rate_controller, p.headingr_p, p.headingr_i, 0, 0, p.roll_lim);
- pid_set_parameters(&altitude_controller, p.altitude_p, 0, 0, 0, p.pitch_lim);
- pid_set_parameters(&offtrack_controller, p.xtrack_p, 0, 0, 0, 60.0f * M_DEG_TO_RAD); //TODO: remove hardcoded value
- }
-
- /* only run controller if attitude changed */
- if (fds[1].revents & POLLIN) {
-
-
- static uint64_t last_run = 0;
- const float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f;
- last_run = hrt_absolute_time();
-
- /* check if there is a new position or setpoint */
- bool pos_updated;
- orb_check(global_pos_sub, &pos_updated);
- bool global_sp_updated;
- orb_check(global_setpoint_sub, &global_sp_updated);
-
- /* load local copies */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
-
- if (pos_updated) {
- orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
- }
-
- if (global_sp_updated) {
- orb_copy(ORB_ID(vehicle_global_position_setpoint), global_setpoint_sub, &global_setpoint);
- start_pos = global_pos; //for now using the current position as the startpoint (= approx. last waypoint because the setpoint switch occurs at the waypoint)
- global_sp_updated_set_once = true;
- psi_track = get_bearing_to_next_waypoint(global_pos.lat, global_pos.lon,
- (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
-
- printf("next wp direction: %0.4f\n", (double)psi_track);
- }
-
- /* Simple Horizontal Control */
- if (global_sp_updated_set_once) {
- // if (counter % 100 == 0)
- // printf("lat_sp %d, ln_sp %d, lat: %d, lon: %d\n", global_setpoint.lat, global_setpoint.lon, global_pos.lat, global_pos.lon);
-
- /* calculate crosstrack error */
- // Only the case of a straight line track following handled so far
- int distance_res = get_distance_to_line(&xtrack_err, (double)global_pos.lat / (double)1e7d, (double)global_pos.lon / (double)1e7d,
- (double)start_pos.lat / (double)1e7d, (double)start_pos.lon / (double)1e7d,
- (double)global_setpoint.lat / (double)1e7d, (double)global_setpoint.lon / (double)1e7d);
-
- // XXX what is xtrack_err.past_end?
- if (distance_res == OK /*&& !xtrack_err.past_end*/) {
-
- float delta_psi_c = pid_calculate(&offtrack_controller, 0, xtrack_err.distance, 0.0f, 0.0f); //p.xtrack_p * xtrack_err.distance
-
- float psi_c = psi_track + delta_psi_c;
- float psi_e = psi_c - att.yaw;
-
- /* wrap difference back onto -pi..pi range */
- psi_e = _wrap_pi(psi_e);
-
- if (verbose) {
- printf("xtrack_err.distance %.4f ", (double)xtrack_err.distance);
- printf("delta_psi_c %.4f ", (double)delta_psi_c);
- printf("psi_c %.4f ", (double)psi_c);
- printf("att.yaw %.4f ", (double)att.yaw);
- printf("psi_e %.4f ", (double)psi_e);
- }
-
- /* calculate roll setpoint, do this artificially around zero */
- float delta_psi_rate_c = pid_calculate(&heading_controller, psi_e, 0.0f, 0.0f, 0.0f);
- float psi_rate_track = 0; //=V_gr/r_track , this will be needed for implementation of arc following
- float psi_rate_c = delta_psi_rate_c + psi_rate_track;
-
- /* limit turn rate */
- if (psi_rate_c > p.headingr_lim) {
- psi_rate_c = p.headingr_lim;
-
- } else if (psi_rate_c < -p.headingr_lim) {
- psi_rate_c = -p.headingr_lim;
- }
-
- float psi_rate_e = psi_rate_c - att.yawspeed;
-
- // XXX sanity check: Assume 10 m/s stall speed and no stall condition
- float ground_speed = sqrtf(global_pos.vx * global_pos.vx + global_pos.vy * global_pos.vy);
-
- if (ground_speed < 10.0f) {
- ground_speed = 10.0f;
- }
-
- float psi_rate_e_scaled = psi_rate_e * ground_speed / 9.81f; //* V_gr / g
-
- attitude_setpoint.roll_body = pid_calculate(&heading_rate_controller, psi_rate_e_scaled, 0.0f, 0.0f, deltaT);
-
- if (verbose) {
- printf("psi_rate_c %.4f ", (double)psi_rate_c);
- printf("psi_rate_e_scaled %.4f ", (double)psi_rate_e_scaled);
- printf("rollbody %.4f\n", (double)attitude_setpoint.roll_body);
- }
-
- if (verbose && counter % 100 == 0)
- printf("xtrack_err.distance: %0.4f, delta_psi_c: %0.4f\n", xtrack_err.distance, delta_psi_c);
-
- } else {
- if (verbose && counter % 100 == 0)
- printf("distance_res: %d, past_end %d\n", distance_res, xtrack_err.past_end);
- }
-
- /* Very simple Altitude Control */
- if (pos_updated) {
-
- //TODO: take care of relative vs. ab. altitude
- attitude_setpoint.pitch_body = pid_calculate(&altitude_controller, global_setpoint.altitude, global_pos.alt, 0.0f, 0.0f);
-
- }
-
- // XXX need speed control
- attitude_setpoint.thrust = 0.7f;
-
- /* publish the attitude setpoint */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), attitude_setpoint_pub, &attitude_setpoint);
-
- /* measure in what intervals the controller runs */
- perf_count(fw_interval_perf);
-
- counter++;
-
- } else {
- // XXX no setpoint, decent default needed (loiter?)
- }
- }
- }
- }
-
- printf("[fixedwing_pos_control] exiting.\n");
- thread_running = false;
-
-
- close(attitude_setpoint_pub);
-
- fflush(stdout);
- exit(0);
-
- return 0;
-
-}
-
-/* Startup Functions */
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- fprintf(stderr, "usage: fixedwing_pos_control {start|stop|status}\n\n");
- exit(1);
-}
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int fixedwing_pos_control_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("fixedwing_pos_control already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn_cmd("fixedwing_pos_control",
- SCHED_DEFAULT,
- SCHED_PRIORITY_MAX - 20,
- 2048,
- fixedwing_pos_control_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- thread_running = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- printf("\tfixedwing_pos_control is running\n");
-
- } else {
- printf("\tfixedwing_pos_control not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
diff --git a/src/modules/fixedwing_pos_control/module.mk b/src/modules/fixedwing_pos_control/module.mk
deleted file mode 100644
index b976377e9..000000000
--- a/src/modules/fixedwing_pos_control/module.mk
+++ /dev/null
@@ -1,40 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Fixedwing PositionControl application
-#
-
-MODULE_COMMAND = fixedwing_pos_control
-
-SRCS = fixedwing_pos_control_main.c
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 5276b1c13..178b590ae 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -134,6 +134,8 @@ private:
struct vehicle_global_position_s _global_pos; /**< global position */
perf_counter_t _loop_perf; /**< loop performance counter */
+ perf_counter_t _nonfinite_input_perf; /**< performance counter for non finite input */
+ perf_counter_t _nonfinite_output_perf; /**< performance counter for non finite output */
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
@@ -273,7 +275,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace att_control
@@ -304,12 +306,14 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
/* publications */
_rate_sp_pub(-1),
- _actuators_0_pub(-1),
_attitude_sp_pub(-1),
+ _actuators_0_pub(-1),
_actuators_1_pub(-1),
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw att control")),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control nonfinite input")),
+ _nonfinite_output_perf(perf_alloc(PC_COUNT, "fw att control nonfinite output")),
/* states */
_setpoint_valid(false)
{
@@ -387,6 +391,10 @@ FixedwingAttitudeControl::~FixedwingAttitudeControl()
} while (_control_task != -1);
}
+ perf_free(_loop_perf);
+ perf_free(_nonfinite_input_perf);
+ perf_free(_nonfinite_output_perf);
+
att_control::g_control = nullptr;
}
@@ -592,6 +600,8 @@ FixedwingAttitudeControl::task_main()
while (!_task_should_exit) {
+ static int loop_counter = 0;
+
/* wait for up to 500ms for data */
int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100);
@@ -672,10 +682,12 @@ FixedwingAttitudeControl::task_main()
float airspeed;
/* if airspeed is not updating, we assume the normal average speed */
- if (!isfinite(_airspeed.true_airspeed_m_s) ||
+ if (bool nonfinite = !isfinite(_airspeed.true_airspeed_m_s) ||
hrt_elapsed_time(&_airspeed.timestamp) > 1e6) {
airspeed = _parameters.airspeed_trim;
-
+ if (nonfinite) {
+ perf_count(_nonfinite_input_perf);
+ }
} else {
airspeed = _airspeed.true_airspeed_m_s;
}
@@ -706,20 +718,21 @@ FixedwingAttitudeControl::task_main()
} else {
/*
* Scale down roll and pitch as the setpoints are radians
- * and a typical remote can only do 45 degrees, the mapping is
- * -1..+1 to -45..+45 degrees or -0.75..+0.75 radians.
+ * and a typical remote can only do around 45 degrees, the mapping is
+ * -1..+1 to -man_roll_max rad..+man_roll_max rad (equivalent for pitch)
*
* With this mapping the stick angle is a 1:1 representation of
- * the commanded attitude. If more than 45 degrees are desired,
- * a scaling parameter can be applied to the remote.
+ * the commanded attitude.
*
* The trim gets subtracted here from the manual setpoint to get
* the intended attitude setpoint. Later, after the rate control step the
* trim is added again to the control signal.
*/
- roll_sp = (_manual.roll * _parameters.man_roll_max - _parameters.trim_roll) + _parameters.rollsp_offset_rad;
- pitch_sp = (-_manual.pitch * _parameters.man_pitch_max - _parameters.trim_pitch) + _parameters.pitchsp_offset_rad;
- throttle_sp = _manual.throttle;
+ roll_sp = (_manual.y * _parameters.man_roll_max - _parameters.trim_roll)
+ + _parameters.rollsp_offset_rad;
+ pitch_sp = -(_manual.x * _parameters.man_pitch_max - _parameters.trim_pitch)
+ + _parameters.pitchsp_offset_rad;
+ throttle_sp = _manual.z;
_actuators.control[4] = _manual.flaps;
/*
@@ -754,7 +767,9 @@ FixedwingAttitudeControl::task_main()
speed_body_v = _att.R[0][1] * _global_pos.vel_n + _att.R[1][1] * _global_pos.vel_e + _att.R[2][1] * _global_pos.vel_d;
speed_body_w = _att.R[0][2] * _global_pos.vel_n + _att.R[1][2] * _global_pos.vel_e + _att.R[2][2] * _global_pos.vel_d;
} else {
- warnx("Did not get a valid R\n");
+ if (loop_counter % 10 == 0) {
+ warnx("Did not get a valid R\n");
+ }
}
/* Run attitude controllers */
@@ -772,7 +787,12 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[0] = (isfinite(roll_u)) ? roll_u + _parameters.trim_roll : _parameters.trim_roll;
if (!isfinite(roll_u)) {
- warnx("roll_u %.4f", roll_u);
+ _roll_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+
+ if (loop_counter % 10 == 0) {
+ warnx("roll_u %.4f", (double)roll_u);
+ }
}
float pitch_u = _pitch_ctrl.control_bodyrate(_att.roll, _att.pitch,
@@ -781,8 +801,22 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[1] = (isfinite(pitch_u)) ? pitch_u + _parameters.trim_pitch : _parameters.trim_pitch;
if (!isfinite(pitch_u)) {
- warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f, airspeed %.4f, airspeed_scaling %.4f, roll_sp %.4f, pitch_sp %.4f, _roll_ctrl.get_desired_rate() %.4f, _pitch_ctrl.get_desired_rate() %.4f att_sp.roll_body %.4f",
- pitch_u, _yaw_ctrl.get_desired_rate(), airspeed, airspeed_scaling, roll_sp, pitch_sp, _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate(), _att_sp.roll_body);
+ _pitch_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("pitch_u %.4f, _yaw_ctrl.get_desired_rate() %.4f,"
+ " airspeed %.4f, airspeed_scaling %.4f,"
+ " roll_sp %.4f, pitch_sp %.4f,"
+ " _roll_ctrl.get_desired_rate() %.4f,"
+ " _pitch_ctrl.get_desired_rate() %.4f"
+ " att_sp.roll_body %.4f",
+ (double)pitch_u, (double)_yaw_ctrl.get_desired_rate(),
+ (double)airspeed, (double)airspeed_scaling,
+ (double)roll_sp, (double)pitch_sp,
+ (double)_roll_ctrl.get_desired_rate(),
+ (double)_pitch_ctrl.get_desired_rate(),
+ (double)_att_sp.roll_body);
+ }
}
float yaw_u = _yaw_ctrl.control_bodyrate(_att.roll, _att.pitch,
@@ -791,16 +825,25 @@ FixedwingAttitudeControl::task_main()
_parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
_actuators.control[2] = (isfinite(yaw_u)) ? yaw_u + _parameters.trim_yaw : _parameters.trim_yaw;
if (!isfinite(yaw_u)) {
- warnx("yaw_u %.4f", yaw_u);
+ _yaw_ctrl.reset_integrator();
+ perf_count(_nonfinite_output_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("yaw_u %.4f", (double)yaw_u);
+ }
}
/* throttle passed through */
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
if (!isfinite(throttle_sp)) {
- warnx("throttle_sp %.4f", throttle_sp);
+ if (loop_counter % 10 == 0) {
+ warnx("throttle_sp %.4f", (double)throttle_sp);
+ }
}
} else {
- warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", roll_sp, pitch_sp);
+ perf_count(_nonfinite_input_perf);
+ if (loop_counter % 10 == 0) {
+ warnx("Non-finite setpoint roll_sp: %.4f, pitch_sp %.4f", (double)roll_sp, (double)pitch_sp);
+ }
}
/*
@@ -825,10 +868,10 @@ FixedwingAttitudeControl::task_main()
} else {
/* manual/direct control */
- _actuators.control[0] = _manual.roll;
- _actuators.control[1] = -_manual.pitch;
- _actuators.control[2] = _manual.yaw;
- _actuators.control[3] = _manual.throttle;
+ _actuators.control[0] = _manual.y;
+ _actuators.control[1] = -_manual.x;
+ _actuators.control[2] = _manual.r;
+ _actuators.control[3] = _manual.z;
_actuators.control[4] = _manual.flaps;
}
@@ -864,6 +907,7 @@ FixedwingAttitudeControl::task_main()
}
+ loop_counter++;
perf_end(_loop_perf);
}
diff --git a/src/modules/fw_att_pos_estimator/estimator.cpp b/src/modules/fw_att_pos_estimator/estimator.cpp
deleted file mode 100644
index c31217393..000000000
--- a/src/modules/fw_att_pos_estimator/estimator.cpp
+++ /dev/null
@@ -1,2248 +0,0 @@
-#include "estimator.h"
-
-#include <string.h>
-
-float Vector3f::length(void) const
-{
- return sqrt(x*x + y*y + z*z);
-}
-
-Vector3f Vector3f::zero(void) const
-{
- Vector3f ret = *this;
- ret.x = 0.0;
- ret.y = 0.0;
- ret.z = 0.0;
- return ret;
-}
-
-Mat3f::Mat3f() {
- x.x = 1.0f;
- x.y = 0.0f;
- x.z = 0.0f;
-
- y.x = 0.0f;
- y.y = 1.0f;
- y.z = 0.0f;
-
- z.x = 0.0f;
- z.y = 0.0f;
- z.z = 1.0f;
-}
-
-Mat3f Mat3f::transpose(void) const
-{
- Mat3f ret = *this;
- swap_var(ret.x.y, ret.y.x);
- swap_var(ret.x.z, ret.z.x);
- swap_var(ret.y.z, ret.z.y);
- return ret;
-}
-
-// overload + operator to provide a vector addition
-Vector3f operator+( Vector3f vecIn1, Vector3f vecIn2)
-{
- Vector3f vecOut;
- vecOut.x = vecIn1.x + vecIn2.x;
- vecOut.y = vecIn1.y + vecIn2.y;
- vecOut.z = vecIn1.z + vecIn2.z;
- return vecOut;
-}
-
-// overload - operator to provide a vector subtraction
-Vector3f operator-( Vector3f vecIn1, Vector3f vecIn2)
-{
- Vector3f vecOut;
- vecOut.x = vecIn1.x - vecIn2.x;
- vecOut.y = vecIn1.y - vecIn2.y;
- vecOut.z = vecIn1.z - vecIn2.z;
- return vecOut;
-}
-
-// overload * operator to provide a matrix vector product
-Vector3f operator*( Mat3f matIn, Vector3f vecIn)
-{
- Vector3f vecOut;
- vecOut.x = matIn.x.x*vecIn.x + matIn.x.y*vecIn.y + matIn.x.z*vecIn.z;
- vecOut.y = matIn.y.x*vecIn.x + matIn.y.y*vecIn.y + matIn.y.z*vecIn.z;
- vecOut.z = matIn.x.x*vecIn.x + matIn.z.y*vecIn.y + matIn.z.z*vecIn.z;
- return vecOut;
-}
-
-// overload % operator to provide a vector cross product
-Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2)
-{
- Vector3f vecOut;
- vecOut.x = vecIn1.y*vecIn2.z - vecIn1.z*vecIn2.y;
- vecOut.y = vecIn1.z*vecIn2.x - vecIn1.x*vecIn2.z;
- vecOut.z = vecIn1.x*vecIn2.y - vecIn1.y*vecIn2.x;
- return vecOut;
-}
-
-// overload * operator to provide a vector scaler product
-Vector3f operator*(Vector3f vecIn1, float sclIn1)
-{
- Vector3f vecOut;
- vecOut.x = vecIn1.x * sclIn1;
- vecOut.y = vecIn1.y * sclIn1;
- vecOut.z = vecIn1.z * sclIn1;
- return vecOut;
-}
-
-// overload * operator to provide a vector scaler product
-Vector3f operator*(float sclIn1, Vector3f vecIn1)
-{
- Vector3f vecOut;
- vecOut.x = vecIn1.x * sclIn1;
- vecOut.y = vecIn1.y * sclIn1;
- vecOut.z = vecIn1.z * sclIn1;
- return vecOut;
-}
-
-void swap_var(float &d1, float &d2)
-{
- float tmp = d1;
- d1 = d2;
- d2 = tmp;
-}
-
-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)
-{
-
-}
-
-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;
- float deltaQuat[4];
- const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS};
-
-// Remove sensor bias errors
- correctedDelAng.x = dAngIMU.x - states[10];
- correctedDelAng.y = dAngIMU.y - states[11];
- correctedDelAng.z = dAngIMU.z - states[12];
- dVelIMU.x = dVelIMU.x;
- dVelIMU.y = dVelIMU.y;
- dVelIMU.z = dVelIMU.z;
-
-// Save current measurements
- Vector3f prevDelAng = correctedDelAng;
-
-// Apply corrections for earths rotation rate and coning errors
-// * and + operators have been overloaded
- correctedDelAng = correctedDelAng - Tnb*earthRateNED*dtIMU + 8.333333333333333e-2f*(prevDelAng % correctedDelAng);
-
-// Convert the rotation vector to its equivalent quaternion
- rotationMag = correctedDelAng.length();
- if (rotationMag < 1e-12f)
- {
- deltaQuat[0] = 1.0;
- deltaQuat[1] = 0.0;
- deltaQuat[2] = 0.0;
- deltaQuat[3] = 0.0;
- }
- else
- {
- deltaQuat[0] = cos(0.5f*rotationMag);
- float rotScaler = (sin(0.5f*rotationMag))/rotationMag;
- deltaQuat[1] = correctedDelAng.x*rotScaler;
- deltaQuat[2] = correctedDelAng.y*rotScaler;
- deltaQuat[3] = correctedDelAng.z*rotScaler;
- }
-
-// Update the quaternions by rotating from the previous attitude through
-// the delta angle rotation quaternion
- qUpdated[0] = states[0]*deltaQuat[0] - states[1]*deltaQuat[1] - states[2]*deltaQuat[2] - states[3]*deltaQuat[3];
- qUpdated[1] = states[0]*deltaQuat[1] + states[1]*deltaQuat[0] + states[2]*deltaQuat[3] - states[3]*deltaQuat[2];
- qUpdated[2] = states[0]*deltaQuat[2] + states[2]*deltaQuat[0] + states[3]*deltaQuat[1] - states[1]*deltaQuat[3];
- qUpdated[3] = states[0]*deltaQuat[3] + states[3]*deltaQuat[0] + states[1]*deltaQuat[2] - states[2]*deltaQuat[1];
-
-// Normalise the quaternions and update the quaternion states
- quatMag = 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 windVelSigma;
- float dAngBiasSigma;
- // float dVelBiasSigma;
- float magEarthSigma;
- float magBodySigma;
- float daxCov;
- float dayCov;
- float dazCov;
- float dvxCov;
- float dvyCov;
- float dvzCov;
- float dvx;
- float dvy;
- float dvz;
- float dax;
- float day;
- float daz;
- float q0;
- float q1;
- float q2;
- float q3;
- float dax_b;
- float day_b;
- float daz_b;
-
- // arrays
- float processNoise[21];
- float SF[14];
- float SG[8];
- float SQ[11];
- float SPP[13] = {0};
- float nextP[21][21];
-
- // calculate covariance prediction process noise
- const float yawVarScale = 1.0f;
- windVelSigma = dt*0.1f;
- dAngBiasSigma = dt*5.0e-7f;
- magEarthSigma = dt*3.0e-4f;
- magBodySigma = dt*3.0e-4f;
- for (uint8_t i= 0; i<=9; i++) processNoise[i] = 1.0e-9f;
- for (uint8_t i=10; i<=12; i++) processNoise[i] = dAngBiasSigma;
- if (onGround) processNoise[12] = dAngBiasSigma * yawVarScale;
- for (uint8_t i=13; i<=14; i++) processNoise[i] = windVelSigma;
- for (uint8_t i=15; i<=17; i++) processNoise[i] = magEarthSigma;
- for (uint8_t i=18; i<=20; i++) processNoise[i] = magBodySigma;
- for (uint8_t i= 0; i<=20; i++) processNoise[i] = sq(processNoise[i]);
-
- // set variables used to calculate covariance growth
- dvx = summedDelVel.x;
- dvy = summedDelVel.y;
- dvz = summedDelVel.z;
- dax = summedDelAng.x;
- day = summedDelAng.y;
- daz = summedDelAng.z;
- q0 = states[0];
- q1 = states[1];
- q2 = states[2];
- q3 = states[3];
- dax_b = states[10];
- day_b = states[11];
- daz_b = states[12];
- daxCov = sq(dt*1.4544411e-2f);
- dayCov = sq(dt*1.4544411e-2f);
- dazCov = sq(dt*1.4544411e-2f);
- if (onGround) dazCov = dazCov * sq(yawVarScale);
- dvxCov = sq(dt*0.5f);
- dvyCov = sq(dt*0.5f);
- dvzCov = sq(dt*0.5f);
-
- // Predicted covariance calculation
- SF[0] = 2*dvx*q1 + 2*dvy*q2 + 2*dvz*q3;
- SF[1] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
- SF[2] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
- SF[3] = day/2 - day_b/2;
- SF[4] = daz/2 - daz_b/2;
- SF[5] = dax/2 - dax_b/2;
- SF[6] = dax_b/2 - dax/2;
- SF[7] = daz_b/2 - daz/2;
- SF[8] = day_b/2 - day/2;
- SF[9] = q1/2;
- SF[10] = q2/2;
- SF[11] = q3/2;
- SF[12] = 2*dvz*q0;
- SF[13] = 2*dvy*q1;
-
- SG[0] = q0/2;
- SG[1] = sq(q3);
- SG[2] = sq(q2);
- SG[3] = sq(q1);
- SG[4] = sq(q0);
- SG[5] = 2*q2*q3;
- SG[6] = 2*q1*q3;
- SG[7] = 2*q1*q2;
-
- SQ[0] = dvzCov*(SG[5] - 2*q0*q1)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvyCov*(SG[5] + 2*q0*q1)*(SG[1] - SG[2] + SG[3] - SG[4]) + dvxCov*(SG[6] - 2*q0*q2)*(SG[7] + 2*q0*q3);
- SQ[1] = dvzCov*(SG[6] + 2*q0*q2)*(SG[1] - SG[2] - SG[3] + SG[4]) - dvxCov*(SG[6] - 2*q0*q2)*(SG[1] + SG[2] - SG[3] - SG[4]) + dvyCov*(SG[5] + 2*q0*q1)*(SG[7] - 2*q0*q3);
- SQ[2] = dvzCov*(SG[5] - 2*q0*q1)*(SG[6] + 2*q0*q2) - dvyCov*(SG[7] - 2*q0*q3)*(SG[1] - SG[2] + SG[3] - SG[4]) - dvxCov*(SG[7] + 2*q0*q3)*(SG[1] + SG[2] - SG[3] - SG[4]);
- SQ[3] = (dayCov*q1*SG[0])/2 - (dazCov*q1*SG[0])/2 - (daxCov*q2*q3)/4;
- SQ[4] = (dazCov*q2*SG[0])/2 - (daxCov*q2*SG[0])/2 - (dayCov*q1*q3)/4;
- SQ[5] = (daxCov*q3*SG[0])/2 - (dayCov*q3*SG[0])/2 - (dazCov*q1*q2)/4;
- SQ[6] = (daxCov*q1*q2)/4 - (dazCov*q3*SG[0])/2 - (dayCov*q1*q2)/4;
- SQ[7] = (dazCov*q1*q3)/4 - (daxCov*q1*q3)/4 - (dayCov*q2*SG[0])/2;
- SQ[8] = (dayCov*q2*q3)/4 - (daxCov*q1*SG[0])/2 - (dazCov*q2*q3)/4;
- SQ[9] = sq(SG[0]);
- SQ[10] = sq(q1);
-
- SPP[0] = SF[12] + SF[13] - 2*dvx*q2;
- SPP[1] = 2*dvx*q0 - 2*dvy*q3 + 2*dvz*q2;
- SPP[2] = 2*dvx*q3 + 2*dvy*q0 - 2*dvz*q1;
- SPP[3] = SF[11];
- SPP[4] = SF[10];
- SPP[5] = SF[9];
- SPP[6] = SF[7];
- SPP[7] = SF[8];
-
- nextP[0][0] = P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3] + (daxCov*SQ[10])/4 + SF[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[7]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[6]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[5]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[4]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) + SPP[3]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) + (dayCov*sq(q2))/4 + (dazCov*sq(q3))/4;
- nextP[0][1] = P[0][1] + SQ[8] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3] + SF[5]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[4]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[7]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[3]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - SPP[4]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]))/2;
- nextP[0][2] = P[0][2] + SQ[7] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3] + SF[3]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[5]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[6]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) - SPP[3]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) + SPP[5]*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]) - (q0*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]))/2;
- nextP[0][3] = P[0][3] + SQ[6] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3] + SF[4]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[3]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[6]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SPP[4]*(P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3]) - SPP[5]*(P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3]) - (q0*(P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3]))/2;
- nextP[0][4] = P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3] + SF[2]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SPP[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) - SPP[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]);
- nextP[0][5] = P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3] + SF[1]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) + SF[0]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]) + SF[2]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) - SPP[0]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]);
- nextP[0][6] = P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3] + SF[1]*(P[0][1] + P[1][1]*SF[6] + P[2][1]*SPP[7] + P[3][1]*SPP[6] + P[10][1]*SPP[5] + P[11][1]*SPP[4] + P[12][1]*SPP[3]) + SF[0]*(P[0][3] + P[1][3]*SF[6] + P[2][3]*SPP[7] + P[3][3]*SPP[6] + P[10][3]*SPP[5] + P[11][3]*SPP[4] + P[12][3]*SPP[3]) + SPP[0]*(P[0][0] + P[1][0]*SF[6] + P[2][0]*SPP[7] + P[3][0]*SPP[6] + P[10][0]*SPP[5] + P[11][0]*SPP[4] + P[12][0]*SPP[3]) - SPP[1]*(P[0][2] + P[1][2]*SF[6] + P[2][2]*SPP[7] + P[3][2]*SPP[6] + P[10][2]*SPP[5] + P[11][2]*SPP[4] + P[12][2]*SPP[3]);
- nextP[0][7] = P[0][7] + P[1][7]*SF[6] + P[2][7]*SPP[7] + P[3][7]*SPP[6] + P[10][7]*SPP[5] + P[11][7]*SPP[4] + P[12][7]*SPP[3] + dt*(P[0][4] + P[1][4]*SF[6] + P[2][4]*SPP[7] + P[3][4]*SPP[6] + P[10][4]*SPP[5] + P[11][4]*SPP[4] + P[12][4]*SPP[3]);
- nextP[0][8] = P[0][8] + P[1][8]*SF[6] + P[2][8]*SPP[7] + P[3][8]*SPP[6] + P[10][8]*SPP[5] + P[11][8]*SPP[4] + P[12][8]*SPP[3] + dt*(P[0][5] + P[1][5]*SF[6] + P[2][5]*SPP[7] + P[3][5]*SPP[6] + P[10][5]*SPP[5] + P[11][5]*SPP[4] + P[12][5]*SPP[3]);
- nextP[0][9] = P[0][9] + P[1][9]*SF[6] + P[2][9]*SPP[7] + P[3][9]*SPP[6] + P[10][9]*SPP[5] + P[11][9]*SPP[4] + P[12][9]*SPP[3] + dt*(P[0][6] + P[1][6]*SF[6] + P[2][6]*SPP[7] + P[3][6]*SPP[6] + P[10][6]*SPP[5] + P[11][6]*SPP[4] + P[12][6]*SPP[3]);
- nextP[0][10] = P[0][10] + P[1][10]*SF[6] + P[2][10]*SPP[7] + P[3][10]*SPP[6] + P[10][10]*SPP[5] + P[11][10]*SPP[4] + P[12][10]*SPP[3];
- nextP[0][11] = P[0][11] + P[1][11]*SF[6] + P[2][11]*SPP[7] + P[3][11]*SPP[6] + P[10][11]*SPP[5] + P[11][11]*SPP[4] + P[12][11]*SPP[3];
- nextP[0][12] = P[0][12] + P[1][12]*SF[6] + P[2][12]*SPP[7] + P[3][12]*SPP[6] + P[10][12]*SPP[5] + P[11][12]*SPP[4] + P[12][12]*SPP[3];
- nextP[0][13] = P[0][13] + P[1][13]*SF[6] + P[2][13]*SPP[7] + P[3][13]*SPP[6] + P[10][13]*SPP[5] + P[11][13]*SPP[4] + P[12][13]*SPP[3];
- nextP[0][14] = P[0][14] + P[1][14]*SF[6] + P[2][14]*SPP[7] + P[3][14]*SPP[6] + P[10][14]*SPP[5] + P[11][14]*SPP[4] + P[12][14]*SPP[3];
- nextP[0][15] = P[0][15] + P[1][15]*SF[6] + P[2][15]*SPP[7] + P[3][15]*SPP[6] + P[10][15]*SPP[5] + P[11][15]*SPP[4] + P[12][15]*SPP[3];
- nextP[0][16] = P[0][16] + P[1][16]*SF[6] + P[2][16]*SPP[7] + P[3][16]*SPP[6] + P[10][16]*SPP[5] + P[11][16]*SPP[4] + P[12][16]*SPP[3];
- nextP[0][17] = P[0][17] + P[1][17]*SF[6] + P[2][17]*SPP[7] + P[3][17]*SPP[6] + P[10][17]*SPP[5] + P[11][17]*SPP[4] + P[12][17]*SPP[3];
- nextP[0][18] = P[0][18] + P[1][18]*SF[6] + P[2][18]*SPP[7] + P[3][18]*SPP[6] + P[10][18]*SPP[5] + P[11][18]*SPP[4] + P[12][18]*SPP[3];
- nextP[0][19] = P[0][19] + P[1][19]*SF[6] + P[2][19]*SPP[7] + P[3][19]*SPP[6] + P[10][19]*SPP[5] + P[11][19]*SPP[4] + P[12][19]*SPP[3];
- nextP[0][20] = P[0][20] + P[1][20]*SF[6] + P[2][20]*SPP[7] + P[3][20]*SPP[6] + P[10][20]*SPP[5] + P[11][20]*SPP[4] + P[12][20]*SPP[3];
- nextP[1][0] = P[1][0] + SQ[8] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2 + SF[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[7]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[6]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[5]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[4]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) + SPP[3]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2);
- nextP[1][1] = P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] + daxCov*SQ[9] - (P[10][1]*q0)/2 + SF[5]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[4]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[7]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[3]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - SPP[4]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) + (dayCov*sq(q3))/4 + (dazCov*sq(q2))/4 - (q0*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2))/2;
- nextP[1][2] = P[1][2] + SQ[5] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2 + SF[3]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[5]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[6]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) - SPP[3]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) + SPP[5]*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2) - (q0*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2))/2;
- nextP[1][3] = P[1][3] + SQ[4] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2 + SF[4]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[3]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[6]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SPP[4]*(P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2) - SPP[5]*(P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2) - (q0*(P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2))/2;
- nextP[1][4] = P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2 + SF[2]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SPP[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) - SPP[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2);
- nextP[1][5] = P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2 + SF[1]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) + SF[0]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2) + SF[2]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) - SPP[0]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2);
- nextP[1][6] = P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2 + SF[1]*(P[1][1] + P[0][1]*SF[5] + P[2][1]*SF[4] + P[3][1]*SPP[7] + P[11][1]*SPP[3] - P[12][1]*SPP[4] - (P[10][1]*q0)/2) + SF[0]*(P[1][3] + P[0][3]*SF[5] + P[2][3]*SF[4] + P[3][3]*SPP[7] + P[11][3]*SPP[3] - P[12][3]*SPP[4] - (P[10][3]*q0)/2) + SPP[0]*(P[1][0] + P[0][0]*SF[5] + P[2][0]*SF[4] + P[3][0]*SPP[7] + P[11][0]*SPP[3] - P[12][0]*SPP[4] - (P[10][0]*q0)/2) - SPP[1]*(P[1][2] + P[0][2]*SF[5] + P[2][2]*SF[4] + P[3][2]*SPP[7] + P[11][2]*SPP[3] - P[12][2]*SPP[4] - (P[10][2]*q0)/2);
- nextP[1][7] = P[1][7] + P[0][7]*SF[5] + P[2][7]*SF[4] + P[3][7]*SPP[7] + P[11][7]*SPP[3] - P[12][7]*SPP[4] - (P[10][7]*q0)/2 + dt*(P[1][4] + P[0][4]*SF[5] + P[2][4]*SF[4] + P[3][4]*SPP[7] + P[11][4]*SPP[3] - P[12][4]*SPP[4] - (P[10][4]*q0)/2);
- nextP[1][8] = P[1][8] + P[0][8]*SF[5] + P[2][8]*SF[4] + P[3][8]*SPP[7] + P[11][8]*SPP[3] - P[12][8]*SPP[4] - (P[10][8]*q0)/2 + dt*(P[1][5] + P[0][5]*SF[5] + P[2][5]*SF[4] + P[3][5]*SPP[7] + P[11][5]*SPP[3] - P[12][5]*SPP[4] - (P[10][5]*q0)/2);
- nextP[1][9] = P[1][9] + P[0][9]*SF[5] + P[2][9]*SF[4] + P[3][9]*SPP[7] + P[11][9]*SPP[3] - P[12][9]*SPP[4] - (P[10][9]*q0)/2 + dt*(P[1][6] + P[0][6]*SF[5] + P[2][6]*SF[4] + P[3][6]*SPP[7] + P[11][6]*SPP[3] - P[12][6]*SPP[4] - (P[10][6]*q0)/2);
- nextP[1][10] = P[1][10] + P[0][10]*SF[5] + P[2][10]*SF[4] + P[3][10]*SPP[7] + P[11][10]*SPP[3] - P[12][10]*SPP[4] - (P[10][10]*q0)/2;
- nextP[1][11] = P[1][11] + P[0][11]*SF[5] + P[2][11]*SF[4] + P[3][11]*SPP[7] + P[11][11]*SPP[3] - P[12][11]*SPP[4] - (P[10][11]*q0)/2;
- nextP[1][12] = P[1][12] + P[0][12]*SF[5] + P[2][12]*SF[4] + P[3][12]*SPP[7] + P[11][12]*SPP[3] - P[12][12]*SPP[4] - (P[10][12]*q0)/2;
- nextP[1][13] = P[1][13] + P[0][13]*SF[5] + P[2][13]*SF[4] + P[3][13]*SPP[7] + P[11][13]*SPP[3] - P[12][13]*SPP[4] - (P[10][13]*q0)/2;
- nextP[1][14] = P[1][14] + P[0][14]*SF[5] + P[2][14]*SF[4] + P[3][14]*SPP[7] + P[11][14]*SPP[3] - P[12][14]*SPP[4] - (P[10][14]*q0)/2;
- nextP[1][15] = P[1][15] + P[0][15]*SF[5] + P[2][15]*SF[4] + P[3][15]*SPP[7] + P[11][15]*SPP[3] - P[12][15]*SPP[4] - (P[10][15]*q0)/2;
- nextP[1][16] = P[1][16] + P[0][16]*SF[5] + P[2][16]*SF[4] + P[3][16]*SPP[7] + P[11][16]*SPP[3] - P[12][16]*SPP[4] - (P[10][16]*q0)/2;
- nextP[1][17] = P[1][17] + P[0][17]*SF[5] + P[2][17]*SF[4] + P[3][17]*SPP[7] + P[11][17]*SPP[3] - P[12][17]*SPP[4] - (P[10][17]*q0)/2;
- nextP[1][18] = P[1][18] + P[0][18]*SF[5] + P[2][18]*SF[4] + P[3][18]*SPP[7] + P[11][18]*SPP[3] - P[12][18]*SPP[4] - (P[10][18]*q0)/2;
- nextP[1][19] = P[1][19] + P[0][19]*SF[5] + P[2][19]*SF[4] + P[3][19]*SPP[7] + P[11][19]*SPP[3] - P[12][19]*SPP[4] - (P[10][19]*q0)/2;
- nextP[1][20] = P[1][20] + P[0][20]*SF[5] + P[2][20]*SF[4] + P[3][20]*SPP[7] + P[11][20]*SPP[3] - P[12][20]*SPP[4] - (P[10][20]*q0)/2;
- nextP[2][0] = P[2][0] + SQ[7] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2 + SF[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[7]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[6]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[5]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[4]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) + SPP[3]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2);
- nextP[2][1] = P[2][1] + SQ[5] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2 + SF[5]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[4]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[7]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[3]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - SPP[4]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) - (q0*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2))/2;
- nextP[2][2] = P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] + dayCov*SQ[9] + (dazCov*SQ[10])/4 - (P[11][2]*q0)/2 + SF[3]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[5]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[6]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) - SPP[3]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) + SPP[5]*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2) + (daxCov*sq(q3))/4 - (q0*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2))/2;
- nextP[2][3] = P[2][3] + SQ[3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2 + SF[4]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[3]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[6]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SPP[4]*(P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2) - SPP[5]*(P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2) - (q0*(P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2))/2;
- nextP[2][4] = P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2 + SF[2]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SPP[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) - SPP[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2);
- nextP[2][5] = P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2 + SF[1]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) + SF[0]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2) + SF[2]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) - SPP[0]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2);
- nextP[2][6] = P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2 + SF[1]*(P[2][1] + P[0][1]*SF[3] + P[3][1]*SF[5] + P[1][1]*SPP[6] - P[10][1]*SPP[3] + P[12][1]*SPP[5] - (P[11][1]*q0)/2) + SF[0]*(P[2][3] + P[0][3]*SF[3] + P[3][3]*SF[5] + P[1][3]*SPP[6] - P[10][3]*SPP[3] + P[12][3]*SPP[5] - (P[11][3]*q0)/2) + SPP[0]*(P[2][0] + P[0][0]*SF[3] + P[3][0]*SF[5] + P[1][0]*SPP[6] - P[10][0]*SPP[3] + P[12][0]*SPP[5] - (P[11][0]*q0)/2) - SPP[1]*(P[2][2] + P[0][2]*SF[3] + P[3][2]*SF[5] + P[1][2]*SPP[6] - P[10][2]*SPP[3] + P[12][2]*SPP[5] - (P[11][2]*q0)/2);
- nextP[2][7] = P[2][7] + P[0][7]*SF[3] + P[3][7]*SF[5] + P[1][7]*SPP[6] - P[10][7]*SPP[3] + P[12][7]*SPP[5] - (P[11][7]*q0)/2 + dt*(P[2][4] + P[0][4]*SF[3] + P[3][4]*SF[5] + P[1][4]*SPP[6] - P[10][4]*SPP[3] + P[12][4]*SPP[5] - (P[11][4]*q0)/2);
- nextP[2][8] = P[2][8] + P[0][8]*SF[3] + P[3][8]*SF[5] + P[1][8]*SPP[6] - P[10][8]*SPP[3] + P[12][8]*SPP[5] - (P[11][8]*q0)/2 + dt*(P[2][5] + P[0][5]*SF[3] + P[3][5]*SF[5] + P[1][5]*SPP[6] - P[10][5]*SPP[3] + P[12][5]*SPP[5] - (P[11][5]*q0)/2);
- nextP[2][9] = P[2][9] + P[0][9]*SF[3] + P[3][9]*SF[5] + P[1][9]*SPP[6] - P[10][9]*SPP[3] + P[12][9]*SPP[5] - (P[11][9]*q0)/2 + dt*(P[2][6] + P[0][6]*SF[3] + P[3][6]*SF[5] + P[1][6]*SPP[6] - P[10][6]*SPP[3] + P[12][6]*SPP[5] - (P[11][6]*q0)/2);
- nextP[2][10] = P[2][10] + P[0][10]*SF[3] + P[3][10]*SF[5] + P[1][10]*SPP[6] - P[10][10]*SPP[3] + P[12][10]*SPP[5] - (P[11][10]*q0)/2;
- nextP[2][11] = P[2][11] + P[0][11]*SF[3] + P[3][11]*SF[5] + P[1][11]*SPP[6] - P[10][11]*SPP[3] + P[12][11]*SPP[5] - (P[11][11]*q0)/2;
- nextP[2][12] = P[2][12] + P[0][12]*SF[3] + P[3][12]*SF[5] + P[1][12]*SPP[6] - P[10][12]*SPP[3] + P[12][12]*SPP[5] - (P[11][12]*q0)/2;
- nextP[2][13] = P[2][13] + P[0][13]*SF[3] + P[3][13]*SF[5] + P[1][13]*SPP[6] - P[10][13]*SPP[3] + P[12][13]*SPP[5] - (P[11][13]*q0)/2;
- nextP[2][14] = P[2][14] + P[0][14]*SF[3] + P[3][14]*SF[5] + P[1][14]*SPP[6] - P[10][14]*SPP[3] + P[12][14]*SPP[5] - (P[11][14]*q0)/2;
- nextP[2][15] = P[2][15] + P[0][15]*SF[3] + P[3][15]*SF[5] + P[1][15]*SPP[6] - P[10][15]*SPP[3] + P[12][15]*SPP[5] - (P[11][15]*q0)/2;
- nextP[2][16] = P[2][16] + P[0][16]*SF[3] + P[3][16]*SF[5] + P[1][16]*SPP[6] - P[10][16]*SPP[3] + P[12][16]*SPP[5] - (P[11][16]*q0)/2;
- nextP[2][17] = P[2][17] + P[0][17]*SF[3] + P[3][17]*SF[5] + P[1][17]*SPP[6] - P[10][17]*SPP[3] + P[12][17]*SPP[5] - (P[11][17]*q0)/2;
- nextP[2][18] = P[2][18] + P[0][18]*SF[3] + P[3][18]*SF[5] + P[1][18]*SPP[6] - P[10][18]*SPP[3] + P[12][18]*SPP[5] - (P[11][18]*q0)/2;
- nextP[2][19] = P[2][19] + P[0][19]*SF[3] + P[3][19]*SF[5] + P[1][19]*SPP[6] - P[10][19]*SPP[3] + P[12][19]*SPP[5] - (P[11][19]*q0)/2;
- nextP[2][20] = P[2][20] + P[0][20]*SF[3] + P[3][20]*SF[5] + P[1][20]*SPP[6] - P[10][20]*SPP[3] + P[12][20]*SPP[5] - (P[11][20]*q0)/2;
- nextP[3][0] = P[3][0] + SQ[6] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2 + SF[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[7]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[6]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[5]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[4]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + SPP[3]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2);
- nextP[3][1] = P[3][1] + SQ[4] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2 + SF[5]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[4]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[7]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[3]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) - SPP[4]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2))/2;
- nextP[3][2] = P[3][2] + SQ[3] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2 + SF[3]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[5]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[6]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) - SPP[3]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) + SPP[5]*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2) - (q0*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2))/2;
- nextP[3][3] = P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] + (dayCov*SQ[10])/4 + dazCov*SQ[9] - (P[12][3]*q0)/2 + SF[4]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[3]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[6]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SPP[4]*(P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2) - SPP[5]*(P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2) + (daxCov*sq(q2))/4 - (q0*(P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2))/2;
- nextP[3][4] = P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2 + SF[2]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SPP[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) - SPP[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2);
- nextP[3][5] = P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2 + SF[1]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) + SF[0]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2) + SF[2]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) - SPP[0]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2);
- nextP[3][6] = P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2 + SF[1]*(P[3][1] + P[0][1]*SF[4] + P[1][1]*SF[3] + P[2][1]*SF[6] + P[10][1]*SPP[4] - P[11][1]*SPP[5] - (P[12][1]*q0)/2) + SF[0]*(P[3][3] + P[0][3]*SF[4] + P[1][3]*SF[3] + P[2][3]*SF[6] + P[10][3]*SPP[4] - P[11][3]*SPP[5] - (P[12][3]*q0)/2) + SPP[0]*(P[3][0] + P[0][0]*SF[4] + P[1][0]*SF[3] + P[2][0]*SF[6] + P[10][0]*SPP[4] - P[11][0]*SPP[5] - (P[12][0]*q0)/2) - SPP[1]*(P[3][2] + P[0][2]*SF[4] + P[1][2]*SF[3] + P[2][2]*SF[6] + P[10][2]*SPP[4] - P[11][2]*SPP[5] - (P[12][2]*q0)/2);
- nextP[3][7] = P[3][7] + P[0][7]*SF[4] + P[1][7]*SF[3] + P[2][7]*SF[6] + P[10][7]*SPP[4] - P[11][7]*SPP[5] - (P[12][7]*q0)/2 + dt*(P[3][4] + P[0][4]*SF[4] + P[1][4]*SF[3] + P[2][4]*SF[6] + P[10][4]*SPP[4] - P[11][4]*SPP[5] - (P[12][4]*q0)/2);
- nextP[3][8] = P[3][8] + P[0][8]*SF[4] + P[1][8]*SF[3] + P[2][8]*SF[6] + P[10][8]*SPP[4] - P[11][8]*SPP[5] - (P[12][8]*q0)/2 + dt*(P[3][5] + P[0][5]*SF[4] + P[1][5]*SF[3] + P[2][5]*SF[6] + P[10][5]*SPP[4] - P[11][5]*SPP[5] - (P[12][5]*q0)/2);
- nextP[3][9] = P[3][9] + P[0][9]*SF[4] + P[1][9]*SF[3] + P[2][9]*SF[6] + P[10][9]*SPP[4] - P[11][9]*SPP[5] - (P[12][9]*q0)/2 + dt*(P[3][6] + P[0][6]*SF[4] + P[1][6]*SF[3] + P[2][6]*SF[6] + P[10][6]*SPP[4] - P[11][6]*SPP[5] - (P[12][6]*q0)/2);
- nextP[3][10] = P[3][10] + P[0][10]*SF[4] + P[1][10]*SF[3] + P[2][10]*SF[6] + P[10][10]*SPP[4] - P[11][10]*SPP[5] - (P[12][10]*q0)/2;
- nextP[3][11] = P[3][11] + P[0][11]*SF[4] + P[1][11]*SF[3] + P[2][11]*SF[6] + P[10][11]*SPP[4] - P[11][11]*SPP[5] - (P[12][11]*q0)/2;
- nextP[3][12] = P[3][12] + P[0][12]*SF[4] + P[1][12]*SF[3] + P[2][12]*SF[6] + P[10][12]*SPP[4] - P[11][12]*SPP[5] - (P[12][12]*q0)/2;
- nextP[3][13] = P[3][13] + P[0][13]*SF[4] + P[1][13]*SF[3] + P[2][13]*SF[6] + P[10][13]*SPP[4] - P[11][13]*SPP[5] - (P[12][13]*q0)/2;
- nextP[3][14] = P[3][14] + P[0][14]*SF[4] + P[1][14]*SF[3] + P[2][14]*SF[6] + P[10][14]*SPP[4] - P[11][14]*SPP[5] - (P[12][14]*q0)/2;
- nextP[3][15] = P[3][15] + P[0][15]*SF[4] + P[1][15]*SF[3] + P[2][15]*SF[6] + P[10][15]*SPP[4] - P[11][15]*SPP[5] - (P[12][15]*q0)/2;
- nextP[3][16] = P[3][16] + P[0][16]*SF[4] + P[1][16]*SF[3] + P[2][16]*SF[6] + P[10][16]*SPP[4] - P[11][16]*SPP[5] - (P[12][16]*q0)/2;
- nextP[3][17] = P[3][17] + P[0][17]*SF[4] + P[1][17]*SF[3] + P[2][17]*SF[6] + P[10][17]*SPP[4] - P[11][17]*SPP[5] - (P[12][17]*q0)/2;
- nextP[3][18] = P[3][18] + P[0][18]*SF[4] + P[1][18]*SF[3] + P[2][18]*SF[6] + P[10][18]*SPP[4] - P[11][18]*SPP[5] - (P[12][18]*q0)/2;
- nextP[3][19] = P[3][19] + P[0][19]*SF[4] + P[1][19]*SF[3] + P[2][19]*SF[6] + P[10][19]*SPP[4] - P[11][19]*SPP[5] - (P[12][19]*q0)/2;
- nextP[3][20] = P[3][20] + P[0][20]*SF[4] + P[1][20]*SF[3] + P[2][20]*SF[6] + P[10][20]*SPP[4] - P[11][20]*SPP[5] - (P[12][20]*q0)/2;
- nextP[4][0] = P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2] + SF[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[7]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[6]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[5]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[4]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) + SPP[3]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]);
- nextP[4][1] = P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2] + SF[5]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[4]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[7]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[3]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - SPP[4]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]))/2;
- nextP[4][2] = P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2] + SF[3]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[5]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[6]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) - SPP[3]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) + SPP[5]*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]) - (q0*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]))/2;
- nextP[4][3] = P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2] + SF[4]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[3]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[6]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SPP[4]*(P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2]) - SPP[5]*(P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2]) - (q0*(P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2]))/2;
- nextP[4][4] = P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2] + dvyCov*sq(SG[7] - 2*q0*q3) + dvzCov*sq(SG[6] + 2*q0*q2) + SF[2]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SPP[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) - SPP[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + dvxCov*sq(SG[1] + SG[2] - SG[3] - SG[4]);
- nextP[4][5] = P[4][5] + SQ[2] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2] + SF[1]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) + SF[0]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]) + SF[2]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) - SPP[0]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]);
- nextP[4][6] = P[4][6] + SQ[1] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2] + SF[1]*(P[4][1] + P[0][1]*SF[2] + P[1][1]*SF[0] + P[2][1]*SPP[0] - P[3][1]*SPP[2]) + SF[0]*(P[4][3] + P[0][3]*SF[2] + P[1][3]*SF[0] + P[2][3]*SPP[0] - P[3][3]*SPP[2]) + SPP[0]*(P[4][0] + P[0][0]*SF[2] + P[1][0]*SF[0] + P[2][0]*SPP[0] - P[3][0]*SPP[2]) - SPP[1]*(P[4][2] + P[0][2]*SF[2] + P[1][2]*SF[0] + P[2][2]*SPP[0] - P[3][2]*SPP[2]);
- nextP[4][7] = P[4][7] + P[0][7]*SF[2] + P[1][7]*SF[0] + P[2][7]*SPP[0] - P[3][7]*SPP[2] + dt*(P[4][4] + P[0][4]*SF[2] + P[1][4]*SF[0] + P[2][4]*SPP[0] - P[3][4]*SPP[2]);
- nextP[4][8] = P[4][8] + P[0][8]*SF[2] + P[1][8]*SF[0] + P[2][8]*SPP[0] - P[3][8]*SPP[2] + dt*(P[4][5] + P[0][5]*SF[2] + P[1][5]*SF[0] + P[2][5]*SPP[0] - P[3][5]*SPP[2]);
- nextP[4][9] = P[4][9] + P[0][9]*SF[2] + P[1][9]*SF[0] + P[2][9]*SPP[0] - P[3][9]*SPP[2] + dt*(P[4][6] + P[0][6]*SF[2] + P[1][6]*SF[0] + P[2][6]*SPP[0] - P[3][6]*SPP[2]);
- nextP[4][10] = P[4][10] + P[0][10]*SF[2] + P[1][10]*SF[0] + P[2][10]*SPP[0] - P[3][10]*SPP[2];
- nextP[4][11] = P[4][11] + P[0][11]*SF[2] + P[1][11]*SF[0] + P[2][11]*SPP[0] - P[3][11]*SPP[2];
- nextP[4][12] = P[4][12] + P[0][12]*SF[2] + P[1][12]*SF[0] + P[2][12]*SPP[0] - P[3][12]*SPP[2];
- nextP[4][13] = P[4][13] + P[0][13]*SF[2] + P[1][13]*SF[0] + P[2][13]*SPP[0] - P[3][13]*SPP[2];
- nextP[4][14] = P[4][14] + P[0][14]*SF[2] + P[1][14]*SF[0] + P[2][14]*SPP[0] - P[3][14]*SPP[2];
- nextP[4][15] = P[4][15] + P[0][15]*SF[2] + P[1][15]*SF[0] + P[2][15]*SPP[0] - P[3][15]*SPP[2];
- nextP[4][16] = P[4][16] + P[0][16]*SF[2] + P[1][16]*SF[0] + P[2][16]*SPP[0] - P[3][16]*SPP[2];
- nextP[4][17] = P[4][17] + P[0][17]*SF[2] + P[1][17]*SF[0] + P[2][17]*SPP[0] - P[3][17]*SPP[2];
- nextP[4][18] = P[4][18] + P[0][18]*SF[2] + P[1][18]*SF[0] + P[2][18]*SPP[0] - P[3][18]*SPP[2];
- nextP[4][19] = P[4][19] + P[0][19]*SF[2] + P[1][19]*SF[0] + P[2][19]*SPP[0] - P[3][19]*SPP[2];
- nextP[4][20] = P[4][20] + P[0][20]*SF[2] + P[1][20]*SF[0] + P[2][20]*SPP[0] - P[3][20]*SPP[2];
- nextP[5][0] = P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0] + SF[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[7]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[6]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[5]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[4]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) + SPP[3]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]);
- nextP[5][1] = P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0] + SF[5]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[4]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[7]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[3]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - SPP[4]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]))/2;
- nextP[5][2] = P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0] + SF[3]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[5]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[6]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) - SPP[3]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) + SPP[5]*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]) - (q0*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]))/2;
- nextP[5][3] = P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0] + SF[4]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[3]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[6]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SPP[4]*(P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0]) - SPP[5]*(P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0]) - (q0*(P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0]))/2;
- nextP[5][4] = P[5][4] + SQ[2] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0] + SF[2]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SPP[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) - SPP[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]);
- nextP[5][5] = P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0] + dvxCov*sq(SG[7] + 2*q0*q3) + dvzCov*sq(SG[5] - 2*q0*q1) + SF[1]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) + SF[0]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]) + SF[2]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) - SPP[0]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + dvyCov*sq(SG[1] - SG[2] + SG[3] - SG[4]);
- nextP[5][6] = P[5][6] + SQ[0] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0] + SF[1]*(P[5][1] + P[0][1]*SF[1] + P[2][1]*SF[0] + P[3][1]*SF[2] - P[1][1]*SPP[0]) + SF[0]*(P[5][3] + P[0][3]*SF[1] + P[2][3]*SF[0] + P[3][3]*SF[2] - P[1][3]*SPP[0]) + SPP[0]*(P[5][0] + P[0][0]*SF[1] + P[2][0]*SF[0] + P[3][0]*SF[2] - P[1][0]*SPP[0]) - SPP[1]*(P[5][2] + P[0][2]*SF[1] + P[2][2]*SF[0] + P[3][2]*SF[2] - P[1][2]*SPP[0]);
- nextP[5][7] = P[5][7] + P[0][7]*SF[1] + P[2][7]*SF[0] + P[3][7]*SF[2] - P[1][7]*SPP[0] + dt*(P[5][4] + P[0][4]*SF[1] + P[2][4]*SF[0] + P[3][4]*SF[2] - P[1][4]*SPP[0]);
- nextP[5][8] = P[5][8] + P[0][8]*SF[1] + P[2][8]*SF[0] + P[3][8]*SF[2] - P[1][8]*SPP[0] + dt*(P[5][5] + P[0][5]*SF[1] + P[2][5]*SF[0] + P[3][5]*SF[2] - P[1][5]*SPP[0]);
- nextP[5][9] = P[5][9] + P[0][9]*SF[1] + P[2][9]*SF[0] + P[3][9]*SF[2] - P[1][9]*SPP[0] + dt*(P[5][6] + P[0][6]*SF[1] + P[2][6]*SF[0] + P[3][6]*SF[2] - P[1][6]*SPP[0]);
- nextP[5][10] = P[5][10] + P[0][10]*SF[1] + P[2][10]*SF[0] + P[3][10]*SF[2] - P[1][10]*SPP[0];
- nextP[5][11] = P[5][11] + P[0][11]*SF[1] + P[2][11]*SF[0] + P[3][11]*SF[2] - P[1][11]*SPP[0];
- nextP[5][12] = P[5][12] + P[0][12]*SF[1] + P[2][12]*SF[0] + P[3][12]*SF[2] - P[1][12]*SPP[0];
- nextP[5][13] = P[5][13] + P[0][13]*SF[1] + P[2][13]*SF[0] + P[3][13]*SF[2] - P[1][13]*SPP[0];
- nextP[5][14] = P[5][14] + P[0][14]*SF[1] + P[2][14]*SF[0] + P[3][14]*SF[2] - P[1][14]*SPP[0];
- nextP[5][15] = P[5][15] + P[0][15]*SF[1] + P[2][15]*SF[0] + P[3][15]*SF[2] - P[1][15]*SPP[0];
- nextP[5][16] = P[5][16] + P[0][16]*SF[1] + P[2][16]*SF[0] + P[3][16]*SF[2] - P[1][16]*SPP[0];
- nextP[5][17] = P[5][17] + P[0][17]*SF[1] + P[2][17]*SF[0] + P[3][17]*SF[2] - P[1][17]*SPP[0];
- nextP[5][18] = P[5][18] + P[0][18]*SF[1] + P[2][18]*SF[0] + P[3][18]*SF[2] - P[1][18]*SPP[0];
- nextP[5][19] = P[5][19] + P[0][19]*SF[1] + P[2][19]*SF[0] + P[3][19]*SF[2] - P[1][19]*SPP[0];
- nextP[5][20] = P[5][20] + P[0][20]*SF[1] + P[2][20]*SF[0] + P[3][20]*SF[2] - P[1][20]*SPP[0];
- nextP[6][0] = P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1] + SF[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[7]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[6]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[5]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[4]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) + SPP[3]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]);
- nextP[6][1] = P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1] + SF[5]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[4]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[7]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[3]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - SPP[4]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]))/2;
- nextP[6][2] = P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1] + SF[3]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[5]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[6]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) - SPP[3]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) + SPP[5]*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]) - (q0*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]))/2;
- nextP[6][3] = P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1] + SF[4]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[3]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[6]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SPP[4]*(P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1]) - SPP[5]*(P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1]) - (q0*(P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1]))/2;
- nextP[6][4] = P[6][4] + SQ[1] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1] + SF[2]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SPP[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) - SPP[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]);
- nextP[6][5] = P[6][5] + SQ[0] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1] + SF[1]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) + SF[0]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + SF[2]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) - SPP[0]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]);
- nextP[6][6] = P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1] + dvxCov*sq(SG[6] - 2*q0*q2) + dvyCov*sq(SG[5] + 2*q0*q1) + SF[1]*(P[6][1] + P[1][1]*SF[1] + P[3][1]*SF[0] + P[0][1]*SPP[0] - P[2][1]*SPP[1]) + SF[0]*(P[6][3] + P[1][3]*SF[1] + P[3][3]*SF[0] + P[0][3]*SPP[0] - P[2][3]*SPP[1]) + SPP[0]*(P[6][0] + P[1][0]*SF[1] + P[3][0]*SF[0] + P[0][0]*SPP[0] - P[2][0]*SPP[1]) - SPP[1]*(P[6][2] + P[1][2]*SF[1] + P[3][2]*SF[0] + P[0][2]*SPP[0] - P[2][2]*SPP[1]) + dvzCov*sq(SG[1] - SG[2] - SG[3] + SG[4]);
- nextP[6][7] = P[6][7] + P[1][7]*SF[1] + P[3][7]*SF[0] + P[0][7]*SPP[0] - P[2][7]*SPP[1] + dt*(P[6][4] + P[1][4]*SF[1] + P[3][4]*SF[0] + P[0][4]*SPP[0] - P[2][4]*SPP[1]);
- nextP[6][8] = P[6][8] + P[1][8]*SF[1] + P[3][8]*SF[0] + P[0][8]*SPP[0] - P[2][8]*SPP[1] + dt*(P[6][5] + P[1][5]*SF[1] + P[3][5]*SF[0] + P[0][5]*SPP[0] - P[2][5]*SPP[1]);
- nextP[6][9] = P[6][9] + P[1][9]*SF[1] + P[3][9]*SF[0] + P[0][9]*SPP[0] - P[2][9]*SPP[1] + dt*(P[6][6] + P[1][6]*SF[1] + P[3][6]*SF[0] + P[0][6]*SPP[0] - P[2][6]*SPP[1]);
- nextP[6][10] = P[6][10] + P[1][10]*SF[1] + P[3][10]*SF[0] + P[0][10]*SPP[0] - P[2][10]*SPP[1];
- nextP[6][11] = P[6][11] + P[1][11]*SF[1] + P[3][11]*SF[0] + P[0][11]*SPP[0] - P[2][11]*SPP[1];
- nextP[6][12] = P[6][12] + P[1][12]*SF[1] + P[3][12]*SF[0] + P[0][12]*SPP[0] - P[2][12]*SPP[1];
- nextP[6][13] = P[6][13] + P[1][13]*SF[1] + P[3][13]*SF[0] + P[0][13]*SPP[0] - P[2][13]*SPP[1];
- nextP[6][14] = P[6][14] + P[1][14]*SF[1] + P[3][14]*SF[0] + P[0][14]*SPP[0] - P[2][14]*SPP[1];
- nextP[6][15] = P[6][15] + P[1][15]*SF[1] + P[3][15]*SF[0] + P[0][15]*SPP[0] - P[2][15]*SPP[1];
- nextP[6][16] = P[6][16] + P[1][16]*SF[1] + P[3][16]*SF[0] + P[0][16]*SPP[0] - P[2][16]*SPP[1];
- nextP[6][17] = P[6][17] + P[1][17]*SF[1] + P[3][17]*SF[0] + P[0][17]*SPP[0] - P[2][17]*SPP[1];
- nextP[6][18] = P[6][18] + P[1][18]*SF[1] + P[3][18]*SF[0] + P[0][18]*SPP[0] - P[2][18]*SPP[1];
- nextP[6][19] = P[6][19] + P[1][19]*SF[1] + P[3][19]*SF[0] + P[0][19]*SPP[0] - P[2][19]*SPP[1];
- nextP[6][20] = P[6][20] + P[1][20]*SF[1] + P[3][20]*SF[0] + P[0][20]*SPP[0] - P[2][20]*SPP[1];
- nextP[7][0] = P[7][0] + P[4][0]*dt + SF[6]*(P[7][1] + P[4][1]*dt) + SPP[7]*(P[7][2] + P[4][2]*dt) + SPP[6]*(P[7][3] + P[4][3]*dt) + SPP[5]*(P[7][10] + P[4][10]*dt) + SPP[4]*(P[7][11] + P[4][11]*dt) + SPP[3]*(P[7][12] + P[4][12]*dt);
- nextP[7][1] = P[7][1] + P[4][1]*dt + SF[5]*(P[7][0] + P[4][0]*dt) + SF[4]*(P[7][2] + P[4][2]*dt) + SPP[7]*(P[7][3] + P[4][3]*dt) + SPP[3]*(P[7][11] + P[4][11]*dt) - SPP[4]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][10] + P[4][10]*dt))/2;
- nextP[7][2] = P[7][2] + P[4][2]*dt + SF[3]*(P[7][0] + P[4][0]*dt) + SF[5]*(P[7][3] + P[4][3]*dt) + SPP[6]*(P[7][1] + P[4][1]*dt) - SPP[3]*(P[7][10] + P[4][10]*dt) + SPP[5]*(P[7][12] + P[4][12]*dt) - (q0*(P[7][11] + P[4][11]*dt))/2;
- nextP[7][3] = P[7][3] + P[4][3]*dt + SF[4]*(P[7][0] + P[4][0]*dt) + SF[3]*(P[7][1] + P[4][1]*dt) + SF[6]*(P[7][2] + P[4][2]*dt) + SPP[4]*(P[7][10] + P[4][10]*dt) - SPP[5]*(P[7][11] + P[4][11]*dt) - (q0*(P[7][12] + P[4][12]*dt))/2;
- nextP[7][4] = P[7][4] + P[4][4]*dt + SF[0]*(P[7][1] + P[4][1]*dt) + SF[2]*(P[7][0] + P[4][0]*dt) + SPP[0]*(P[7][2] + P[4][2]*dt) - SPP[2]*(P[7][3] + P[4][3]*dt);
- nextP[7][5] = P[7][5] + P[4][5]*dt + SF[1]*(P[7][0] + P[4][0]*dt) + SF[0]*(P[7][2] + P[4][2]*dt) + SF[2]*(P[7][3] + P[4][3]*dt) - SPP[0]*(P[7][1] + P[4][1]*dt);
- nextP[7][6] = P[7][6] + P[4][6]*dt + SF[1]*(P[7][1] + P[4][1]*dt) + SF[0]*(P[7][3] + P[4][3]*dt) + SPP[0]*(P[7][0] + P[4][0]*dt) - SPP[1]*(P[7][2] + P[4][2]*dt);
- nextP[7][7] = P[7][7] + P[4][7]*dt + dt*(P[7][4] + P[4][4]*dt);
- nextP[7][8] = P[7][8] + P[4][8]*dt + dt*(P[7][5] + P[4][5]*dt);
- nextP[7][9] = P[7][9] + P[4][9]*dt + dt*(P[7][6] + P[4][6]*dt);
- nextP[7][10] = P[7][10] + P[4][10]*dt;
- nextP[7][11] = P[7][11] + P[4][11]*dt;
- nextP[7][12] = P[7][12] + P[4][12]*dt;
- nextP[7][13] = P[7][13] + P[4][13]*dt;
- nextP[7][14] = P[7][14] + P[4][14]*dt;
- nextP[7][15] = P[7][15] + P[4][15]*dt;
- nextP[7][16] = P[7][16] + P[4][16]*dt;
- nextP[7][17] = P[7][17] + P[4][17]*dt;
- nextP[7][18] = P[7][18] + P[4][18]*dt;
- nextP[7][19] = P[7][19] + P[4][19]*dt;
- nextP[7][20] = P[7][20] + P[4][20]*dt;
- nextP[8][0] = P[8][0] + P[5][0]*dt + SF[6]*(P[8][1] + P[5][1]*dt) + SPP[7]*(P[8][2] + P[5][2]*dt) + SPP[6]*(P[8][3] + P[5][3]*dt) + SPP[5]*(P[8][10] + P[5][10]*dt) + SPP[4]*(P[8][11] + P[5][11]*dt) + SPP[3]*(P[8][12] + P[5][12]*dt);
- nextP[8][1] = P[8][1] + P[5][1]*dt + SF[5]*(P[8][0] + P[5][0]*dt) + SF[4]*(P[8][2] + P[5][2]*dt) + SPP[7]*(P[8][3] + P[5][3]*dt) + SPP[3]*(P[8][11] + P[5][11]*dt) - SPP[4]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][10] + P[5][10]*dt))/2;
- nextP[8][2] = P[8][2] + P[5][2]*dt + SF[3]*(P[8][0] + P[5][0]*dt) + SF[5]*(P[8][3] + P[5][3]*dt) + SPP[6]*(P[8][1] + P[5][1]*dt) - SPP[3]*(P[8][10] + P[5][10]*dt) + SPP[5]*(P[8][12] + P[5][12]*dt) - (q0*(P[8][11] + P[5][11]*dt))/2;
- nextP[8][3] = P[8][3] + P[5][3]*dt + SF[4]*(P[8][0] + P[5][0]*dt) + SF[3]*(P[8][1] + P[5][1]*dt) + SF[6]*(P[8][2] + P[5][2]*dt) + SPP[4]*(P[8][10] + P[5][10]*dt) - SPP[5]*(P[8][11] + P[5][11]*dt) - (q0*(P[8][12] + P[5][12]*dt))/2;
- nextP[8][4] = P[8][4] + P[5][4]*dt + SF[0]*(P[8][1] + P[5][1]*dt) + SF[2]*(P[8][0] + P[5][0]*dt) + SPP[0]*(P[8][2] + P[5][2]*dt) - SPP[2]*(P[8][3] + P[5][3]*dt);
- nextP[8][5] = P[8][5] + P[5][5]*dt + SF[1]*(P[8][0] + P[5][0]*dt) + SF[0]*(P[8][2] + P[5][2]*dt) + SF[2]*(P[8][3] + P[5][3]*dt) - SPP[0]*(P[8][1] + P[5][1]*dt);
- nextP[8][6] = P[8][6] + P[5][6]*dt + SF[1]*(P[8][1] + P[5][1]*dt) + SF[0]*(P[8][3] + P[5][3]*dt) + SPP[0]*(P[8][0] + P[5][0]*dt) - SPP[1]*(P[8][2] + P[5][2]*dt);
- nextP[8][7] = P[8][7] + P[5][7]*dt + dt*(P[8][4] + P[5][4]*dt);
- nextP[8][8] = P[8][8] + P[5][8]*dt + dt*(P[8][5] + P[5][5]*dt);
- nextP[8][9] = P[8][9] + P[5][9]*dt + dt*(P[8][6] + P[5][6]*dt);
- nextP[8][10] = P[8][10] + P[5][10]*dt;
- nextP[8][11] = P[8][11] + P[5][11]*dt;
- nextP[8][12] = P[8][12] + P[5][12]*dt;
- nextP[8][13] = P[8][13] + P[5][13]*dt;
- nextP[8][14] = P[8][14] + P[5][14]*dt;
- nextP[8][15] = P[8][15] + P[5][15]*dt;
- nextP[8][16] = P[8][16] + P[5][16]*dt;
- nextP[8][17] = P[8][17] + P[5][17]*dt;
- nextP[8][18] = P[8][18] + P[5][18]*dt;
- nextP[8][19] = P[8][19] + P[5][19]*dt;
- nextP[8][20] = P[8][20] + P[5][20]*dt;
- nextP[9][0] = P[9][0] + P[6][0]*dt + SF[6]*(P[9][1] + P[6][1]*dt) + SPP[7]*(P[9][2] + P[6][2]*dt) + SPP[6]*(P[9][3] + P[6][3]*dt) + SPP[5]*(P[9][10] + P[6][10]*dt) + SPP[4]*(P[9][11] + P[6][11]*dt) + SPP[3]*(P[9][12] + P[6][12]*dt);
- nextP[9][1] = P[9][1] + P[6][1]*dt + SF[5]*(P[9][0] + P[6][0]*dt) + SF[4]*(P[9][2] + P[6][2]*dt) + SPP[7]*(P[9][3] + P[6][3]*dt) + SPP[3]*(P[9][11] + P[6][11]*dt) - SPP[4]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][10] + P[6][10]*dt))/2;
- nextP[9][2] = P[9][2] + P[6][2]*dt + SF[3]*(P[9][0] + P[6][0]*dt) + SF[5]*(P[9][3] + P[6][3]*dt) + SPP[6]*(P[9][1] + P[6][1]*dt) - SPP[3]*(P[9][10] + P[6][10]*dt) + SPP[5]*(P[9][12] + P[6][12]*dt) - (q0*(P[9][11] + P[6][11]*dt))/2;
- nextP[9][3] = P[9][3] + P[6][3]*dt + SF[4]*(P[9][0] + P[6][0]*dt) + SF[3]*(P[9][1] + P[6][1]*dt) + SF[6]*(P[9][2] + P[6][2]*dt) + SPP[4]*(P[9][10] + P[6][10]*dt) - SPP[5]*(P[9][11] + P[6][11]*dt) - (q0*(P[9][12] + P[6][12]*dt))/2;
- nextP[9][4] = P[9][4] + P[6][4]*dt + SF[0]*(P[9][1] + P[6][1]*dt) + SF[2]*(P[9][0] + P[6][0]*dt) + SPP[0]*(P[9][2] + P[6][2]*dt) - SPP[2]*(P[9][3] + P[6][3]*dt);
- nextP[9][5] = P[9][5] + P[6][5]*dt + SF[1]*(P[9][0] + P[6][0]*dt) + SF[0]*(P[9][2] + P[6][2]*dt) + SF[2]*(P[9][3] + P[6][3]*dt) - SPP[0]*(P[9][1] + P[6][1]*dt);
- nextP[9][6] = P[9][6] + P[6][6]*dt + SF[1]*(P[9][1] + P[6][1]*dt) + SF[0]*(P[9][3] + P[6][3]*dt) + SPP[0]*(P[9][0] + P[6][0]*dt) - SPP[1]*(P[9][2] + P[6][2]*dt);
- nextP[9][7] = P[9][7] + P[6][7]*dt + dt*(P[9][4] + P[6][4]*dt);
- nextP[9][8] = P[9][8] + P[6][8]*dt + dt*(P[9][5] + P[6][5]*dt);
- nextP[9][9] = P[9][9] + P[6][9]*dt + dt*(P[9][6] + P[6][6]*dt);
- nextP[9][10] = P[9][10] + P[6][10]*dt;
- nextP[9][11] = P[9][11] + P[6][11]*dt;
- nextP[9][12] = P[9][12] + P[6][12]*dt;
- nextP[9][13] = P[9][13] + P[6][13]*dt;
- nextP[9][14] = P[9][14] + P[6][14]*dt;
- nextP[9][15] = P[9][15] + P[6][15]*dt;
- nextP[9][16] = P[9][16] + P[6][16]*dt;
- nextP[9][17] = P[9][17] + P[6][17]*dt;
- nextP[9][18] = P[9][18] + P[6][18]*dt;
- nextP[9][19] = P[9][19] + P[6][19]*dt;
- nextP[9][20] = P[9][20] + P[6][20]*dt;
- nextP[10][0] = P[10][0] + P[10][1]*SF[6] + P[10][2]*SPP[7] + P[10][3]*SPP[6] + P[10][10]*SPP[5] + P[10][11]*SPP[4] + P[10][12]*SPP[3];
- nextP[10][1] = P[10][1] + P[10][0]*SF[5] + P[10][2]*SF[4] + P[10][3]*SPP[7] + P[10][11]*SPP[3] - P[10][12]*SPP[4] - (P[10][10]*q0)/2;
- nextP[10][2] = P[10][2] + P[10][0]*SF[3] + P[10][3]*SF[5] + P[10][1]*SPP[6] - P[10][10]*SPP[3] + P[10][12]*SPP[5] - (P[10][11]*q0)/2;
- nextP[10][3] = P[10][3] + P[10][0]*SF[4] + P[10][1]*SF[3] + P[10][2]*SF[6] + P[10][10]*SPP[4] - P[10][11]*SPP[5] - (P[10][12]*q0)/2;
- nextP[10][4] = P[10][4] + P[10][1]*SF[0] + P[10][0]*SF[2] + P[10][2]*SPP[0] - P[10][3]*SPP[2];
- nextP[10][5] = P[10][5] + P[10][0]*SF[1] + P[10][2]*SF[0] + P[10][3]*SF[2] - P[10][1]*SPP[0];
- nextP[10][6] = P[10][6] + P[10][1]*SF[1] + P[10][3]*SF[0] + P[10][0]*SPP[0] - P[10][2]*SPP[1];
- nextP[10][7] = P[10][7] + P[10][4]*dt;
- nextP[10][8] = P[10][8] + P[10][5]*dt;
- nextP[10][9] = P[10][9] + P[10][6]*dt;
- nextP[10][10] = P[10][10];
- nextP[10][11] = P[10][11];
- nextP[10][12] = P[10][12];
- nextP[10][13] = P[10][13];
- nextP[10][14] = P[10][14];
- nextP[10][15] = P[10][15];
- nextP[10][16] = P[10][16];
- nextP[10][17] = P[10][17];
- nextP[10][18] = P[10][18];
- nextP[10][19] = P[10][19];
- nextP[10][20] = P[10][20];
- nextP[11][0] = P[11][0] + P[11][1]*SF[6] + P[11][2]*SPP[7] + P[11][3]*SPP[6] + P[11][10]*SPP[5] + P[11][11]*SPP[4] + P[11][12]*SPP[3];
- nextP[11][1] = P[11][1] + P[11][0]*SF[5] + P[11][2]*SF[4] + P[11][3]*SPP[7] + P[11][11]*SPP[3] - P[11][12]*SPP[4] - (P[11][10]*q0)/2;
- nextP[11][2] = P[11][2] + P[11][0]*SF[3] + P[11][3]*SF[5] + P[11][1]*SPP[6] - P[11][10]*SPP[3] + P[11][12]*SPP[5] - (P[11][11]*q0)/2;
- nextP[11][3] = P[11][3] + P[11][0]*SF[4] + P[11][1]*SF[3] + P[11][2]*SF[6] + P[11][10]*SPP[4] - P[11][11]*SPP[5] - (P[11][12]*q0)/2;
- nextP[11][4] = P[11][4] + P[11][1]*SF[0] + P[11][0]*SF[2] + P[11][2]*SPP[0] - P[11][3]*SPP[2];
- nextP[11][5] = P[11][5] + P[11][0]*SF[1] + P[11][2]*SF[0] + P[11][3]*SF[2] - P[11][1]*SPP[0];
- nextP[11][6] = P[11][6] + P[11][1]*SF[1] + P[11][3]*SF[0] + P[11][0]*SPP[0] - P[11][2]*SPP[1];
- nextP[11][7] = P[11][7] + P[11][4]*dt;
- nextP[11][8] = P[11][8] + P[11][5]*dt;
- nextP[11][9] = P[11][9] + P[11][6]*dt;
- nextP[11][10] = P[11][10];
- nextP[11][11] = P[11][11];
- nextP[11][12] = P[11][12];
- nextP[11][13] = P[11][13];
- nextP[11][14] = P[11][14];
- nextP[11][15] = P[11][15];
- nextP[11][16] = P[11][16];
- nextP[11][17] = P[11][17];
- nextP[11][18] = P[11][18];
- nextP[11][19] = P[11][19];
- nextP[11][20] = P[11][20];
- nextP[12][0] = P[12][0] + P[12][1]*SF[6] + P[12][2]*SPP[7] + P[12][3]*SPP[6] + P[12][10]*SPP[5] + P[12][11]*SPP[4] + P[12][12]*SPP[3];
- nextP[12][1] = P[12][1] + P[12][0]*SF[5] + P[12][2]*SF[4] + P[12][3]*SPP[7] + P[12][11]*SPP[3] - P[12][12]*SPP[4] - (P[12][10]*q0)/2;
- nextP[12][2] = P[12][2] + P[12][0]*SF[3] + P[12][3]*SF[5] + P[12][1]*SPP[6] - P[12][10]*SPP[3] + P[12][12]*SPP[5] - (P[12][11]*q0)/2;
- nextP[12][3] = P[12][3] + P[12][0]*SF[4] + P[12][1]*SF[3] + P[12][2]*SF[6] + P[12][10]*SPP[4] - P[12][11]*SPP[5] - (P[12][12]*q0)/2;
- nextP[12][4] = P[12][4] + P[12][1]*SF[0] + P[12][0]*SF[2] + P[12][2]*SPP[0] - P[12][3]*SPP[2];
- nextP[12][5] = P[12][5] + P[12][0]*SF[1] + P[12][2]*SF[0] + P[12][3]*SF[2] - P[12][1]*SPP[0];
- nextP[12][6] = P[12][6] + P[12][1]*SF[1] + P[12][3]*SF[0] + P[12][0]*SPP[0] - P[12][2]*SPP[1];
- nextP[12][7] = P[12][7] + P[12][4]*dt;
- nextP[12][8] = P[12][8] + P[12][5]*dt;
- nextP[12][9] = P[12][9] + P[12][6]*dt;
- nextP[12][10] = P[12][10];
- nextP[12][11] = P[12][11];
- nextP[12][12] = P[12][12];
- nextP[12][13] = P[12][13];
- nextP[12][14] = P[12][14];
- nextP[12][15] = P[12][15];
- nextP[12][16] = P[12][16];
- nextP[12][17] = P[12][17];
- nextP[12][18] = P[12][18];
- nextP[12][19] = P[12][19];
- nextP[12][20] = P[12][20];
- nextP[13][0] = P[13][0] + P[13][1]*SF[6] + P[13][2]*SPP[7] + P[13][3]*SPP[6] + P[13][10]*SPP[5] + P[13][11]*SPP[4] + P[13][12]*SPP[3];
- nextP[13][1] = P[13][1] + P[13][0]*SF[5] + P[13][2]*SF[4] + P[13][3]*SPP[7] + P[13][11]*SPP[3] - P[13][12]*SPP[4] - (P[13][10]*q0)/2;
- nextP[13][2] = P[13][2] + P[13][0]*SF[3] + P[13][3]*SF[5] + P[13][1]*SPP[6] - P[13][10]*SPP[3] + P[13][12]*SPP[5] - (P[13][11]*q0)/2;
- nextP[13][3] = P[13][3] + P[13][0]*SF[4] + P[13][1]*SF[3] + P[13][2]*SF[6] + P[13][10]*SPP[4] - P[13][11]*SPP[5] - (P[13][12]*q0)/2;
- nextP[13][4] = P[13][4] + P[13][1]*SF[0] + P[13][0]*SF[2] + P[13][2]*SPP[0] - P[13][3]*SPP[2];
- nextP[13][5] = P[13][5] + P[13][0]*SF[1] + P[13][2]*SF[0] + P[13][3]*SF[2] - P[13][1]*SPP[0];
- nextP[13][6] = P[13][6] + P[13][1]*SF[1] + P[13][3]*SF[0] + P[13][0]*SPP[0] - P[13][2]*SPP[1];
- nextP[13][7] = P[13][7] + P[13][4]*dt;
- nextP[13][8] = P[13][8] + P[13][5]*dt;
- nextP[13][9] = P[13][9] + P[13][6]*dt;
- nextP[13][10] = P[13][10];
- nextP[13][11] = P[13][11];
- nextP[13][12] = P[13][12];
- nextP[13][13] = P[13][13];
- nextP[13][14] = P[13][14];
- nextP[13][15] = P[13][15];
- nextP[13][16] = P[13][16];
- nextP[13][17] = P[13][17];
- nextP[13][18] = P[13][18];
- nextP[13][19] = P[13][19];
- nextP[13][20] = P[13][20];
- nextP[14][0] = P[14][0] + P[14][1]*SF[6] + P[14][2]*SPP[7] + P[14][3]*SPP[6] + P[14][10]*SPP[5] + P[14][11]*SPP[4] + P[14][12]*SPP[3];
- nextP[14][1] = P[14][1] + P[14][0]*SF[5] + P[14][2]*SF[4] + P[14][3]*SPP[7] + P[14][11]*SPP[3] - P[14][12]*SPP[4] - (P[14][10]*q0)/2;
- nextP[14][2] = P[14][2] + P[14][0]*SF[3] + P[14][3]*SF[5] + P[14][1]*SPP[6] - P[14][10]*SPP[3] + P[14][12]*SPP[5] - (P[14][11]*q0)/2;
- nextP[14][3] = P[14][3] + P[14][0]*SF[4] + P[14][1]*SF[3] + P[14][2]*SF[6] + P[14][10]*SPP[4] - P[14][11]*SPP[5] - (P[14][12]*q0)/2;
- nextP[14][4] = P[14][4] + P[14][1]*SF[0] + P[14][0]*SF[2] + P[14][2]*SPP[0] - P[14][3]*SPP[2];
- nextP[14][5] = P[14][5] + P[14][0]*SF[1] + P[14][2]*SF[0] + P[14][3]*SF[2] - P[14][1]*SPP[0];
- nextP[14][6] = P[14][6] + P[14][1]*SF[1] + P[14][3]*SF[0] + P[14][0]*SPP[0] - P[14][2]*SPP[1];
- nextP[14][7] = P[14][7] + P[14][4]*dt;
- nextP[14][8] = P[14][8] + P[14][5]*dt;
- nextP[14][9] = P[14][9] + P[14][6]*dt;
- nextP[14][10] = P[14][10];
- nextP[14][11] = P[14][11];
- nextP[14][12] = P[14][12];
- nextP[14][13] = P[14][13];
- nextP[14][14] = P[14][14];
- nextP[14][15] = P[14][15];
- nextP[14][16] = P[14][16];
- nextP[14][17] = P[14][17];
- nextP[14][18] = P[14][18];
- nextP[14][19] = P[14][19];
- nextP[14][20] = P[14][20];
- nextP[15][0] = P[15][0] + P[15][1]*SF[6] + P[15][2]*SPP[7] + P[15][3]*SPP[6] + P[15][10]*SPP[5] + P[15][11]*SPP[4] + P[15][12]*SPP[3];
- nextP[15][1] = P[15][1] + P[15][0]*SF[5] + P[15][2]*SF[4] + P[15][3]*SPP[7] + P[15][11]*SPP[3] - P[15][12]*SPP[4] - (P[15][10]*q0)/2;
- nextP[15][2] = P[15][2] + P[15][0]*SF[3] + P[15][3]*SF[5] + P[15][1]*SPP[6] - P[15][10]*SPP[3] + P[15][12]*SPP[5] - (P[15][11]*q0)/2;
- nextP[15][3] = P[15][3] + P[15][0]*SF[4] + P[15][1]*SF[3] + P[15][2]*SF[6] + P[15][10]*SPP[4] - P[15][11]*SPP[5] - (P[15][12]*q0)/2;
- nextP[15][4] = P[15][4] + P[15][1]*SF[0] + P[15][0]*SF[2] + P[15][2]*SPP[0] - P[15][3]*SPP[2];
- nextP[15][5] = P[15][5] + P[15][0]*SF[1] + P[15][2]*SF[0] + P[15][3]*SF[2] - P[15][1]*SPP[0];
- nextP[15][6] = P[15][6] + P[15][1]*SF[1] + P[15][3]*SF[0] + P[15][0]*SPP[0] - P[15][2]*SPP[1];
- nextP[15][7] = P[15][7] + P[15][4]*dt;
- nextP[15][8] = P[15][8] + P[15][5]*dt;
- nextP[15][9] = P[15][9] + P[15][6]*dt;
- nextP[15][10] = P[15][10];
- nextP[15][11] = P[15][11];
- nextP[15][12] = P[15][12];
- nextP[15][13] = P[15][13];
- nextP[15][14] = P[15][14];
- nextP[15][15] = P[15][15];
- nextP[15][16] = P[15][16];
- nextP[15][17] = P[15][17];
- nextP[15][18] = P[15][18];
- nextP[15][19] = P[15][19];
- nextP[15][20] = P[15][20];
- nextP[16][0] = P[16][0] + P[16][1]*SF[6] + P[16][2]*SPP[7] + P[16][3]*SPP[6] + P[16][10]*SPP[5] + P[16][11]*SPP[4] + P[16][12]*SPP[3];
- nextP[16][1] = P[16][1] + P[16][0]*SF[5] + P[16][2]*SF[4] + P[16][3]*SPP[7] + P[16][11]*SPP[3] - P[16][12]*SPP[4] - (P[16][10]*q0)/2;
- nextP[16][2] = P[16][2] + P[16][0]*SF[3] + P[16][3]*SF[5] + P[16][1]*SPP[6] - P[16][10]*SPP[3] + P[16][12]*SPP[5] - (P[16][11]*q0)/2;
- nextP[16][3] = P[16][3] + P[16][0]*SF[4] + P[16][1]*SF[3] + P[16][2]*SF[6] + P[16][10]*SPP[4] - P[16][11]*SPP[5] - (P[16][12]*q0)/2;
- nextP[16][4] = P[16][4] + P[16][1]*SF[0] + P[16][0]*SF[2] + P[16][2]*SPP[0] - P[16][3]*SPP[2];
- nextP[16][5] = P[16][5] + P[16][0]*SF[1] + P[16][2]*SF[0] + P[16][3]*SF[2] - P[16][1]*SPP[0];
- nextP[16][6] = P[16][6] + P[16][1]*SF[1] + P[16][3]*SF[0] + P[16][0]*SPP[0] - P[16][2]*SPP[1];
- nextP[16][7] = P[16][7] + P[16][4]*dt;
- nextP[16][8] = P[16][8] + P[16][5]*dt;
- nextP[16][9] = P[16][9] + P[16][6]*dt;
- nextP[16][10] = P[16][10];
- nextP[16][11] = P[16][11];
- nextP[16][12] = P[16][12];
- nextP[16][13] = P[16][13];
- nextP[16][14] = P[16][14];
- nextP[16][15] = P[16][15];
- nextP[16][16] = P[16][16];
- nextP[16][17] = P[16][17];
- nextP[16][18] = P[16][18];
- nextP[16][19] = P[16][19];
- nextP[16][20] = P[16][20];
- nextP[17][0] = P[17][0] + P[17][1]*SF[6] + P[17][2]*SPP[7] + P[17][3]*SPP[6] + P[17][10]*SPP[5] + P[17][11]*SPP[4] + P[17][12]*SPP[3];
- nextP[17][1] = P[17][1] + P[17][0]*SF[5] + P[17][2]*SF[4] + P[17][3]*SPP[7] + P[17][11]*SPP[3] - P[17][12]*SPP[4] - (P[17][10]*q0)/2;
- nextP[17][2] = P[17][2] + P[17][0]*SF[3] + P[17][3]*SF[5] + P[17][1]*SPP[6] - P[17][10]*SPP[3] + P[17][12]*SPP[5] - (P[17][11]*q0)/2;
- nextP[17][3] = P[17][3] + P[17][0]*SF[4] + P[17][1]*SF[3] + P[17][2]*SF[6] + P[17][10]*SPP[4] - P[17][11]*SPP[5] - (P[17][12]*q0)/2;
- nextP[17][4] = P[17][4] + P[17][1]*SF[0] + P[17][0]*SF[2] + P[17][2]*SPP[0] - P[17][3]*SPP[2];
- nextP[17][5] = P[17][5] + P[17][0]*SF[1] + P[17][2]*SF[0] + P[17][3]*SF[2] - P[17][1]*SPP[0];
- nextP[17][6] = P[17][6] + P[17][1]*SF[1] + P[17][3]*SF[0] + P[17][0]*SPP[0] - P[17][2]*SPP[1];
- nextP[17][7] = P[17][7] + P[17][4]*dt;
- nextP[17][8] = P[17][8] + P[17][5]*dt;
- nextP[17][9] = P[17][9] + P[17][6]*dt;
- nextP[17][10] = P[17][10];
- nextP[17][11] = P[17][11];
- nextP[17][12] = P[17][12];
- nextP[17][13] = P[17][13];
- nextP[17][14] = P[17][14];
- nextP[17][15] = P[17][15];
- nextP[17][16] = P[17][16];
- nextP[17][17] = P[17][17];
- nextP[17][18] = P[17][18];
- nextP[17][19] = P[17][19];
- nextP[17][20] = P[17][20];
- nextP[18][0] = P[18][0] + P[18][1]*SF[6] + P[18][2]*SPP[7] + P[18][3]*SPP[6] + P[18][10]*SPP[5] + P[18][11]*SPP[4] + P[18][12]*SPP[3];
- nextP[18][1] = P[18][1] + P[18][0]*SF[5] + P[18][2]*SF[4] + P[18][3]*SPP[7] + P[18][11]*SPP[3] - P[18][12]*SPP[4] - (P[18][10]*q0)/2;
- nextP[18][2] = P[18][2] + P[18][0]*SF[3] + P[18][3]*SF[5] + P[18][1]*SPP[6] - P[18][10]*SPP[3] + P[18][12]*SPP[5] - (P[18][11]*q0)/2;
- nextP[18][3] = P[18][3] + P[18][0]*SF[4] + P[18][1]*SF[3] + P[18][2]*SF[6] + P[18][10]*SPP[4] - P[18][11]*SPP[5] - (P[18][12]*q0)/2;
- nextP[18][4] = P[18][4] + P[18][1]*SF[0] + P[18][0]*SF[2] + P[18][2]*SPP[0] - P[18][3]*SPP[2];
- nextP[18][5] = P[18][5] + P[18][0]*SF[1] + P[18][2]*SF[0] + P[18][3]*SF[2] - P[18][1]*SPP[0];
- nextP[18][6] = P[18][6] + P[18][1]*SF[1] + P[18][3]*SF[0] + P[18][0]*SPP[0] - P[18][2]*SPP[1];
- nextP[18][7] = P[18][7] + P[18][4]*dt;
- nextP[18][8] = P[18][8] + P[18][5]*dt;
- nextP[18][9] = P[18][9] + P[18][6]*dt;
- nextP[18][10] = P[18][10];
- nextP[18][11] = P[18][11];
- nextP[18][12] = P[18][12];
- nextP[18][13] = P[18][13];
- nextP[18][14] = P[18][14];
- nextP[18][15] = P[18][15];
- nextP[18][16] = P[18][16];
- nextP[18][17] = P[18][17];
- nextP[18][18] = P[18][18];
- nextP[18][19] = P[18][19];
- nextP[18][20] = P[18][20];
- nextP[19][0] = P[19][0] + P[19][1]*SF[6] + P[19][2]*SPP[7] + P[19][3]*SPP[6] + P[19][10]*SPP[5] + P[19][11]*SPP[4] + P[19][12]*SPP[3];
- nextP[19][1] = P[19][1] + P[19][0]*SF[5] + P[19][2]*SF[4] + P[19][3]*SPP[7] + P[19][11]*SPP[3] - P[19][12]*SPP[4] - (P[19][10]*q0)/2;
- nextP[19][2] = P[19][2] + P[19][0]*SF[3] + P[19][3]*SF[5] + P[19][1]*SPP[6] - P[19][10]*SPP[3] + P[19][12]*SPP[5] - (P[19][11]*q0)/2;
- nextP[19][3] = P[19][3] + P[19][0]*SF[4] + P[19][1]*SF[3] + P[19][2]*SF[6] + P[19][10]*SPP[4] - P[19][11]*SPP[5] - (P[19][12]*q0)/2;
- nextP[19][4] = P[19][4] + P[19][1]*SF[0] + P[19][0]*SF[2] + P[19][2]*SPP[0] - P[19][3]*SPP[2];
- nextP[19][5] = P[19][5] + P[19][0]*SF[1] + P[19][2]*SF[0] + P[19][3]*SF[2] - P[19][1]*SPP[0];
- nextP[19][6] = P[19][6] + P[19][1]*SF[1] + P[19][3]*SF[0] + P[19][0]*SPP[0] - P[19][2]*SPP[1];
- nextP[19][7] = P[19][7] + P[19][4]*dt;
- nextP[19][8] = P[19][8] + P[19][5]*dt;
- nextP[19][9] = P[19][9] + P[19][6]*dt;
- nextP[19][10] = P[19][10];
- nextP[19][11] = P[19][11];
- nextP[19][12] = P[19][12];
- nextP[19][13] = P[19][13];
- nextP[19][14] = P[19][14];
- nextP[19][15] = P[19][15];
- nextP[19][16] = P[19][16];
- nextP[19][17] = P[19][17];
- nextP[19][18] = P[19][18];
- nextP[19][19] = P[19][19];
- nextP[19][20] = P[19][20];
- nextP[20][0] = P[20][0] + P[20][1]*SF[6] + P[20][2]*SPP[7] + P[20][3]*SPP[6] + P[20][10]*SPP[5] + P[20][11]*SPP[4] + P[20][12]*SPP[3];
- nextP[20][1] = P[20][1] + P[20][0]*SF[5] + P[20][2]*SF[4] + P[20][3]*SPP[7] + P[20][11]*SPP[3] - P[20][12]*SPP[4] - (P[20][10]*q0)/2;
- nextP[20][2] = P[20][2] + P[20][0]*SF[3] + P[20][3]*SF[5] + P[20][1]*SPP[6] - P[20][10]*SPP[3] + P[20][12]*SPP[5] - (P[20][11]*q0)/2;
- nextP[20][3] = P[20][3] + P[20][0]*SF[4] + P[20][1]*SF[3] + P[20][2]*SF[6] + P[20][10]*SPP[4] - P[20][11]*SPP[5] - (P[20][12]*q0)/2;
- nextP[20][4] = P[20][4] + P[20][1]*SF[0] + P[20][0]*SF[2] + P[20][2]*SPP[0] - P[20][3]*SPP[2];
- nextP[20][5] = P[20][5] + P[20][0]*SF[1] + P[20][2]*SF[0] + P[20][3]*SF[2] - P[20][1]*SPP[0];
- nextP[20][6] = P[20][6] + P[20][1]*SF[1] + P[20][3]*SF[0] + P[20][0]*SPP[0] - P[20][2]*SPP[1];
- nextP[20][7] = P[20][7] + P[20][4]*dt;
- nextP[20][8] = P[20][8] + P[20][5]*dt;
- nextP[20][9] = P[20][9] + P[20][6]*dt;
- nextP[20][10] = P[20][10];
- nextP[20][11] = P[20][11];
- nextP[20][12] = P[20][12];
- nextP[20][13] = P[20][13];
- nextP[20][14] = P[20][14];
- nextP[20][15] = P[20][15];
- nextP[20][16] = P[20][16];
- nextP[20][17] = P[20][17];
- nextP[20][18] = P[20][18];
- nextP[20][19] = P[20][19];
- nextP[20][20] = P[20][20];
-
- for (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);
-
- 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 *initQuat)
-{
- float initialRoll, initialPitch;
- float cosRoll, sinRoll, cosPitch, sinPitch;
- float magX, magY;
- float initialHdg, cosHeading, sinHeading;
-
- initialRoll = atan2(-ay, -az);
- initialPitch = atan2(ax, -az);
-
- cosRoll = cosf(initialRoll);
- sinRoll = sinf(initialRoll);
- cosPitch = cosf(initialPitch);
- sinPitch = sinf(initialPitch);
-
- magX = mx * cosPitch + my * sinRoll * sinPitch + mz * cosRoll * sinPitch;
-
- magY = my * cosRoll - mz * sinRoll;
-
- initialHdg = atan2f(-magY, magX);
-
- cosRoll = cosf(initialRoll * 0.5f);
- sinRoll = sinf(initialRoll * 0.5f);
-
- cosPitch = cosf(initialPitch * 0.5f);
- sinPitch = sinf(initialPitch * 0.5f);
-
- cosHeading = cosf(initialHdg * 0.5f);
- sinHeading = sinf(initialHdg * 0.5f);
-
- initQuat[0] = cosRoll * cosPitch * cosHeading + sinRoll * sinPitch * sinHeading;
- initQuat[1] = sinRoll * cosPitch * cosHeading - cosRoll * sinPitch * sinHeading;
- initQuat[2] = cosRoll * sinPitch * cosHeading + sinRoll * cosPitch * sinHeading;
- initQuat[3] = cosRoll * cosPitch * sinHeading - sinRoll * sinPitch * cosHeading;
-}
-
-void AttPosEKF::InitializeDynamic(float (&initvelNED)[3])
-{
-
- // Clear the init flag
- statesInitialised = false;
-
- 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, 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])
-{
- //store initial lat,long and height
- latRef = gpsLat;
- lonRef = gpsLon;
- hgtRef = gpsHgt;
-
- memset(&last_ekf_error, 0, sizeof(last_ekf_error));
-
- InitializeDynamic(initvelNED);
-}
-
-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/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 7f13df785..5b877cd77 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -89,6 +89,7 @@
#include <launchdetection/LaunchDetector.h>
#include <ecl/l1/ecl_l1_pos_controller.h>
#include <external_lgpl/tecs/tecs.h>
+#include <drivers/drv_range_finder.h>
#include "landingslope.h"
@@ -134,6 +135,7 @@ private:
int _params_sub; /**< notification of parameter updates */
int _manual_control_sub; /**< notification of manual control updates */
int _sensor_combined_sub; /**< for body frame accelerations */
+ int _range_finder_sub; /**< range finder subscription */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint */
orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */
@@ -147,13 +149,14 @@ private:
struct vehicle_global_position_s _global_pos; /**< global vehicle position */
struct position_setpoint_triplet_s _pos_sp_triplet; /**< triplet of mission items */
struct sensor_combined_s _sensor_combined; /**< for body frame accelerations */
+ struct range_finder_report _range_finder; /**< range finder report */
perf_counter_t _loop_perf; /**< loop performance counter */
bool _setpoint_valid; /**< flag if the position control setpoint is valid */
/** manual control states */
- float _seatbelt_hold_heading; /**< heading the system should hold in seatbelt mode */
+ float _altctrl_hold_heading; /**< heading the system should hold in altctrl mode */
double _loiter_hold_lat;
double _loiter_hold_lon;
float _loiter_hold_alt;
@@ -181,7 +184,7 @@ private:
/* Landingslope object */
Landingslope landingslope;
- float flare_curve_alt_last;
+ float flare_curve_alt_rel_last;
/* heading hold */
float target_bearing;
@@ -239,6 +242,7 @@ private:
float land_flare_alt_relative;
float land_thrust_lim_alt_relative;
float land_heading_hold_horizontal_distance;
+ float range_finder_rel_alt;
} _parameters; /**< local copies of interesting parameters */
@@ -283,6 +287,7 @@ private:
param_t land_flare_alt_relative;
param_t land_thrust_lim_alt_relative;
param_t land_heading_hold_horizontal_distance;
+ param_t range_finder_rel_alt;
} _parameter_handles; /**< handles for interesting parameters */
@@ -309,6 +314,12 @@ private:
bool vehicle_airspeed_poll();
/**
+ * Check for range finder updates.
+ */
+ bool range_finder_poll();
+
+
+ /**
* Check for position updates.
*/
void vehicle_attitude_poll();
@@ -329,6 +340,11 @@ private:
void navigation_capabilities_publish();
/**
+ * Get the relative alt either from the difference between estimate and waypoint or from the laser range finder
+ */
+ float get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt);
+
+ /**
* Control position.
*/
bool control_position(const math::Vector<2> &global_pos, const math::Vector<2> &ground_speed,
@@ -345,7 +361,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
/*
* Reset takeoff state
@@ -384,6 +400,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_control_mode_sub(-1),
_params_sub(-1),
_manual_control_sub(-1),
+ _range_finder_sub(-1),
/* publications */
_attitude_sp_pub(-1),
@@ -401,9 +418,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
land_motor_lim(false),
land_onslope(false),
launch_detected(false),
- last_manual(false),
usePreTakeoffThrust(false),
- flare_curve_alt_last(0.0f),
+ last_manual(false),
+ flare_curve_alt_rel_last(0.0f),
launchDetector(),
_airspeed_error(0.0f),
_airspeed_valid(false),
@@ -417,7 +434,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
_control_mode(),
_global_pos(),
_pos_sp_triplet(),
- _sensor_combined()
+ _sensor_combined(),
+ _range_finder()
{
_nav_capabilities.turn_distance = 0.0f;
@@ -442,6 +460,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT");
_parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT");
_parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST");
+ _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT");
_parameter_handles.time_const = param_find("FW_T_TIME_CONST");
_parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN");
@@ -531,6 +550,8 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative));
param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance));
+ param_get(_parameter_handles.range_finder_rel_alt, &(_parameters.range_finder_rel_alt));
+
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
@@ -626,6 +647,20 @@ FixedwingPositionControl::vehicle_airspeed_poll()
return airspeed_updated;
}
+bool
+FixedwingPositionControl::range_finder_poll()
+{
+ /* check if there is a range finder measurement */
+ bool range_finder_updated;
+ orb_check(_range_finder_sub, &range_finder_updated);
+
+ if (range_finder_updated) {
+ orb_copy(ORB_ID(sensor_range_finder), _range_finder_sub, &_range_finder);
+ }
+
+ return range_finder_updated;
+}
+
void
FixedwingPositionControl::vehicle_attitude_poll()
{
@@ -754,6 +789,23 @@ void FixedwingPositionControl::navigation_capabilities_publish()
}
}
+float FixedwingPositionControl::get_relative_landingalt(float land_setpoint_alt, float current_alt, const struct range_finder_report &range_finder, float range_finder_use_relative_alt)
+{
+ float rel_alt_estimated = current_alt - land_setpoint_alt;
+
+ /* only use range finder if:
+ * parameter (range_finder_use_relative_alt) > 0
+ * the measurement is valid
+ * the estimated relative altitude (from global altitude estimate and landing waypoint) <= range_finder_use_relative_alt
+ */
+ if (range_finder_use_relative_alt < 0 || !range_finder.valid || rel_alt_estimated > range_finder_use_relative_alt ) {
+ return rel_alt_estimated;
+ }
+
+ return range_finder.distance;
+
+}
+
bool
FixedwingPositionControl::control_position(const math::Vector<2> &current_position, const math::Vector<2> &ground_speed,
const struct position_setpoint_triplet_s &pos_sp_triplet)
@@ -896,12 +948,14 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
- float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt);
+ float L_altitude_rel = landingslope.getLandingSlopeRelativeAltitude(L_wp_distance);
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
- float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float landing_slope_alt_rel_desired = landingslope.getLandingSlopeRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
+
+ float relative_alt = get_relative_landingalt(_pos_sp_triplet.current.alt, _global_pos.alt, _range_finder, _parameters.range_finder_rel_alt);
- if ( (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
+ if ( (relative_alt < landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out
/* land with minimal speed */
@@ -911,7 +965,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* kill the throttle if param requests it */
throttle_max = _parameters.throttle_max;
- if (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.motor_lim_relative_alt() || land_motor_lim) {
+ if (relative_alt < landingslope.motor_lim_relative_alt() || land_motor_lim) {
throttle_max = math::min(throttle_max, _parameters.throttle_land_max);
if (!land_motor_lim) {
land_motor_lim = true;
@@ -920,16 +974,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
- float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt);
+ float flare_curve_alt_rel = landingslope.getFlareCurveRelativeAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
/* avoid climbout */
- if ((flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical) || land_stayonground)
+ if ((flare_curve_alt_rel_last < flare_curve_alt_rel && land_noreturn_vertical) || land_stayonground)
{
- flare_curve_alt = pos_sp_triplet.current.alt;
+ flare_curve_alt_rel = 0.0f; // stay on ground
land_stayonground = true;
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, flare_curve_alt, calculate_target_airspeed(airspeed_land),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + flare_curve_alt_rel, calculate_target_airspeed(airspeed_land),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, flare_pitch_angle_rad,
0.0f, throttle_max, throttle_land,
@@ -941,7 +995,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
//warnx("Landing: flare, _global_pos.alt %.1f, flare_curve_alt %.1f, flare_curve_alt_last %.1f, flare_length %.1f, wp_distance %.1f", _global_pos.alt, flare_curve_alt, flare_curve_alt_last, flare_length, wp_distance);
- flare_curve_alt_last = flare_curve_alt;
+ flare_curve_alt_rel_last = flare_curve_alt_rel;
} else {
/* intersect glide slope:
@@ -949,20 +1003,20 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
* if current position is higher or within 10m of slope follow the glide slope
* if current position is below slope -10m continue on maximum of previous wp altitude or L_altitude until the intersection with the slope
* */
- float altitude_desired = _global_pos.alt;
- if (_global_pos.alt > landing_slope_alt_desired - 10.0f) {
+ float altitude_desired_rel = relative_alt;
+ if (relative_alt > landing_slope_alt_rel_desired - 10.0f) {
/* stay on slope */
- altitude_desired = landing_slope_alt_desired;
+ altitude_desired_rel = landing_slope_alt_rel_desired;
if (!land_onslope) {
mavlink_log_info(_mavlink_fd, "#audio: Landing, on slope");
land_onslope = true;
}
} else {
/* continue horizontally */
- altitude_desired = math::max(_global_pos.alt, L_altitude);
+ altitude_desired_rel = math::max(relative_alt, L_altitude_rel);
}
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, altitude_desired, calculate_target_airspeed(airspeed_approach),
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _pos_sp_triplet.current.alt + relative_alt, _pos_sp_triplet.current.alt + altitude_desired_rel, calculate_target_airspeed(airspeed_approach),
_airspeed.indicated_airspeed_m_s, eas2tas,
false, math::radians(_parameters.pitch_limit_min),
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
@@ -1051,16 +1105,16 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
_att_sp.roll_reset_integral = true;
}
- } else if (0/* easy mode enabled */) {
+ } else if (0/* posctrl mode enabled */) {
- /** EASY FLIGHT **/
+ /** POSCTRL FLIGHT **/
- if (0/* switched from another mode to easy */) {
- _seatbelt_hold_heading = _att.yaw;
+ if (0/* switched from another mode to posctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* easy on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* posctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.r;
}
//XXX not used
@@ -1073,44 +1127,44 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
// climb_out = true;
// }
- /* if in seatbelt mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
+ _manual.z;
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
_att_sp.roll_body = _l1_control.nav_roll();
_att_sp.yaw_body = _l1_control.nav_bearing();
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
false, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
_parameters.pitch_limit_min, _parameters.pitch_limit_max);
- } else if (0/* seatbelt mode enabled */) {
+ } else if (0/* altctrl mode enabled */) {
- /** SEATBELT FLIGHT **/
+ /** ALTCTRL FLIGHT **/
- if (0/* switched from another mode to seatbelt */) {
- _seatbelt_hold_heading = _att.yaw;
+ if (0/* switched from another mode to altctrl */) {
+ _altctrl_hold_heading = _att.yaw;
}
- if (0/* seatbelt on and manual control yaw non-zero */) {
- _seatbelt_hold_heading = _att.yaw + _manual.yaw;
+ if (0/* altctrl on and manual control yaw non-zero */) {
+ _altctrl_hold_heading = _att.yaw + _manual.r;
}
- /* if in seatbelt mode, set airspeed based on manual control */
+ /* if in altctrl mode, set airspeed based on manual control */
// XXX check if ground speed undershoot should be applied here
- float seatbelt_airspeed = _parameters.airspeed_min +
+ float altctrl_airspeed = _parameters.airspeed_min +
(_parameters.airspeed_max - _parameters.airspeed_min) *
- _manual.throttle;
+ _manual.z;
/* user switched off throttle */
- if (_manual.throttle < 0.1f) {
+ if (_manual.z < 0.1f) {
throttle_max = 0.0f;
/* switch to pure pitch based altitude control, give up speed */
_tecs.set_speed_weight(0.0f);
@@ -1120,15 +1174,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
bool climb_out = false;
/* user wants to climb out */
- if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) {
+ if (_manual.x > 0.3f && _manual.z > 0.8f) {
climb_out = true;
}
- _l1_control.navigate_heading(_seatbelt_hold_heading, _att.yaw, ground_speed);
- _att_sp.roll_body = _manual.roll;
- _att_sp.yaw_body = _manual.yaw;
- _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.pitch * 2.0f,
- seatbelt_airspeed,
+ _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed);
+ _att_sp.roll_body = _manual.y;
+ _att_sp.yaw_body = _manual.r;
+ _tecs.update_pitch_throttle(_R_nb, _att.pitch, _global_pos.alt, _global_pos.alt + _manual.x * 2.0f,
+ altctrl_airspeed,
_airspeed.indicated_airspeed_m_s, eas2tas,
climb_out, _parameters.pitch_limit_min,
_parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise,
@@ -1185,6 +1239,7 @@ FixedwingPositionControl::task_main()
_airspeed_sub = orb_subscribe(ORB_ID(airspeed));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_control_mode_sub, 200);
@@ -1264,6 +1319,7 @@ FixedwingPositionControl::task_main()
vehicle_setpoint_poll();
vehicle_sensor_combined_poll();
vehicle_airspeed_poll();
+ range_finder_poll();
// vehicle_baro_poll();
math::Vector<2> ground_speed(_global_pos.vel_n, _global_pos.vel_e);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 37f06dbe5..f258f77da 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -375,3 +375,14 @@ PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f);
* @group L1 Control
*/
PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f);
+
+/**
+ * Relative altitude threshold for range finder measurements for use during landing
+ *
+ * range finder measurements will only be used if the estimated relative altitude (gobal_pos.alt - landing_waypoint.alt) is < FW_LND_RFRALT
+ * set to < 0 to disable
+ * the correct value of this parameter depends on your range measuring device as well as on the terrain at the landing location
+ *
+ * @group L1 Control
+ */
+PARAM_DEFINE_FLOAT(FW_LND_RFRALT, -1.0f);
diff --git a/src/modules/fw_pos_control_l1/landingslope.cpp b/src/modules/fw_pos_control_l1/landingslope.cpp
index e5f7023ae..8ce465fe8 100644
--- a/src/modules/fw_pos_control_l1/landingslope.cpp
+++ b/src/modules/fw_pos_control_l1/landingslope.cpp
@@ -69,26 +69,46 @@ void Landingslope::calculateSlopeValues()
_horizontal_slope_displacement = (_flare_length - _d1);
}
-float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude)
+float Landingslope::getLandingSlopeRelativeAltitude(float wp_landing_distance)
{
- return Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad);
+ return Landingslope::getLandingSlopeRelativeAltitude(wp_landing_distance, _horizontal_slope_displacement, _landing_slope_angle_rad);
}
-float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude)
+float Landingslope::getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp)
{
/* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
- return getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude);
+ return getLandingSlopeRelativeAltitude(wp_landing_distance);
+ else
+ return 0.0f;
+}
+
+float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude)
+{
+ return Landingslope::getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad);
+}
+
+float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude)
+{
+ /* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */
+ if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
+ return getLandingSlopeAbsoluteAltitude(wp_landing_distance, wp_altitude);
else
return wp_altitude;
}
-float Landingslope::getFlareCurveAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude)
+float Landingslope::getFlareCurveRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp)
{
/* If airplane is in front of waypoint return flare curve altitude, else return waypoint altitude */
if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f))
- return wp_landing_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt;
+ return _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt;
else
- return wp_landing_altitude;
+ return 0.0f;
+}
+
+float Landingslope::getFlareCurveAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude)
+{
+
+ return wp_landing_altitude + getFlareCurveRelativeAltitudeSave(wp_landing_distance, bearing_lastwp_currwp, bearing_airplane_currwp);
}
diff --git a/src/modules/fw_pos_control_l1/landingslope.h b/src/modules/fw_pos_control_l1/landingslope.h
index 76d65a55f..b54fd501c 100644
--- a/src/modules/fw_pos_control_l1/landingslope.h
+++ b/src/modules/fw_pos_control_l1/landingslope.h
@@ -63,11 +63,26 @@ public:
Landingslope() {}
~Landingslope() {}
+
+ /**
+ *
+ * @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ */
+ float getLandingSlopeRelativeAltitude(float wp_landing_distance);
+
+ /**
+ *
+ * @return relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ * Performs check if aircraft is in front of waypoint to avoid climbout
+ */
+ float getLandingSlopeRelativeAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp);
+
+
/**
*
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
*/
- float getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude);
+ float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_altitude);
/**
*
@@ -78,11 +93,20 @@ public:
/**
*
+ * @return Relative altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
+ */
+ __EXPORT static float getLandingSlopeRelativeAltitude(float wp_landing_distance, float horizontal_slope_displacement, float landing_slope_angle_rad)
+ {
+ return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad); //flare_relative_alt is negative
+ }
+
+ /**
+ *
* @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance
*/
__EXPORT static float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude, float horizontal_slope_displacement, float landing_slope_angle_rad)
{
- return (wp_landing_distance - horizontal_slope_displacement) * tanf(landing_slope_angle_rad) + wp_landing_altitude; //flare_relative_alt is negative
+ return getLandingSlopeRelativeAltitude(wp_landing_distance, horizontal_slope_displacement, landing_slope_angle_rad) + wp_landing_altitude;
}
/**
@@ -95,8 +119,9 @@ public:
}
+ float getFlareCurveRelativeAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp);
- float getFlareCurveAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude);
+ float getFlareCurveAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude);
void update(float landing_slope_angle_rad,
float flare_relative_alt,
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 7ecca0d65..bb1ad86ef 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -149,10 +149,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
instance = Mavlink::get_instance(6);
break;
#endif
- }
-
- /* no valid instance, bail */
- if (!instance) {
+ default:
return;
}
@@ -189,9 +186,18 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
/* If the wait until transmit flag is on, only transmit after we've received messages.
Otherwise, transmit all the time. */
if (instance->should_transmit()) {
- ssize_t ret = write(uart, ch, desired);
+
+ /* check if there is space in the buffer, let it overflow else */
+ if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) {
+
+ if (desired > buf_free) {
+ desired = buf_free;
+ }
+ }
+
+ ssize_t ret = write(uart, ch, desired);
if (ret != desired) {
- // XXX do something here, but change to using FIONWRITE and OS buf size for detection
+ warnx("TX FAIL");
}
}
@@ -202,9 +208,9 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length
static void usage(void);
Mavlink::Mavlink() :
- next(nullptr),
_device_name(DEFAULT_DEVICE_NAME),
_task_should_exit(false),
+ next(nullptr),
_mavlink_fd(-1),
_task_running(false),
_hil_enabled(false),
@@ -225,7 +231,6 @@ Mavlink::Mavlink() :
_subscribe_to_stream_rate(0.0f),
_flow_control_enabled(true),
_message_buffer({}),
-
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "mavlink"))
{
@@ -410,7 +415,7 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self)
void
Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self)
{
-
+
Mavlink *inst;
LL_FOREACH(_mavlink_instances, inst) {
if (inst != self) {
@@ -727,9 +732,9 @@ int Mavlink::mavlink_pm_send_param(param_t param)
if (param == PARAM_INVALID) { return 1; }
/* buffers for param transmission */
- static char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
+ char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN];
float val_buf;
- static mavlink_message_t tx_msg;
+ mavlink_message_t tx_msg;
/* query parameter type */
param_type_t type = param_type(param);
@@ -881,7 +886,7 @@ int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item
switch (mavlink_mission_item->command) {
case MAV_CMD_NAV_TAKEOFF:
- mission_item->pitch_min = mavlink_mission_item->param2;
+ mission_item->pitch_min = mavlink_mission_item->param1;
break;
default:
@@ -1523,6 +1528,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg)
void
Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg)
{
+ uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
+
uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg);
mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len);
@@ -1535,6 +1542,8 @@ Mavlink::mavlink_missionlib_send_gcs_string(const char *string)
{
const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN;
mavlink_statustext_t statustext;
+ statustext.severity = MAV_SEVERITY_INFO;
+
int i = 0;
while (i < len - 1) {
@@ -2017,14 +2026,14 @@ Mavlink::task_main(int argc, char *argv[])
if (_subscribe_to_stream != nullptr) {
if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) {
if (_subscribe_to_stream_rate > 0.0f) {
- warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, _subscribe_to_stream_rate);
+ warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate);
} else {
warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name);
}
} else {
- warnx("stream %s not found", _subscribe_to_stream, _device_name);
+ warnx("stream %s on device %s not found", _subscribe_to_stream, _device_name);
}
delete _subscribe_to_stream;
@@ -2191,7 +2200,7 @@ Mavlink::start(int argc, char *argv[])
task_spawn_cmd(buf,
SCHED_DEFAULT,
SCHED_PRIORITY_DEFAULT,
- 2048,
+ 1950,
(main_t)&Mavlink::start_helper,
(const char **)argv);
@@ -2230,7 +2239,6 @@ Mavlink::stream(int argc, char *argv[])
const char *device_name = DEFAULT_DEVICE_NAME;
float rate = -1.0f;
const char *stream_name = nullptr;
- int ch;
argc -= 2;
argv += 2;
@@ -2267,7 +2275,7 @@ Mavlink::stream(int argc, char *argv[])
i++;
}
- if (!err_flag && rate >= 0.0 && stream_name != nullptr) {
+ if (!err_flag && rate >= 0.0f && stream_name != nullptr) {
Mavlink *inst = get_instance_for_device(device_name);
if (inst != nullptr) {
diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h
index 1bf51fd31..25c0da820 100644
--- a/src/modules/mavlink/mavlink_main.h
+++ b/src/modules/mavlink/mavlink_main.h
@@ -221,8 +221,6 @@ private:
int _mavlink_fd;
bool _task_running;
- perf_counter_t _loop_perf; /**< loop performance counter */
-
/* states */
bool _hil_enabled; /**< Hardware In the Loop mode */
bool _use_hil_gps; /**< Accept GPS HIL messages (for example from an external motion capturing system to fake indoor gps) */
@@ -237,7 +235,6 @@ private:
orb_advert_t _mission_pub;
struct mission_s mission;
- uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN];
MAVLINK_MODE _mode;
uint8_t _mavlink_wpm_comp_id;
@@ -283,7 +280,7 @@ private:
pthread_mutex_t _message_buffer_mutex;
-
+ perf_counter_t _loop_perf; /**< loop performance counter */
/**
* Send one parameter.
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 678ce1645..933478f56 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -124,18 +124,22 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | (status->is_rotary_wing ? MAV_MODE_FLAG_STABILIZE_ENABLED : 0);
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL;
- } else if (status->main_state == MAIN_STATE_SEATBELT) {
+ } else if (status->main_state == MAIN_STATE_ALTCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_SEATBELT;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ALTCTL;
- } else if (status->main_state == MAIN_STATE_EASY) {
+ } else if (status->main_state == MAIN_STATE_POSCTL) {
*mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
- custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_EASY;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_POSCTL;
} else if (status->main_state == MAIN_STATE_AUTO) {
*mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED;
custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_AUTO;
custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_READY;
+
+ } else if (status->main_state == MAIN_STATE_ACRO) {
+ *mavlink_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_ACRO;
}
} else {
@@ -819,11 +823,11 @@ protected:
void send(const hrt_abstime t)
{
- bool updated = status_sub->update(t);
- updated |= pos_sp_triplet_sub->update(t);
- updated |= act_sub->update(t);
+ bool updated = act_sub->update(t);
+ (void)pos_sp_triplet_sub->update(t);
+ (void)status_sub->update(t);
- if (updated) {
+ 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;
@@ -1138,10 +1142,10 @@ protected:
if (manual_sub->update(t)) {
mavlink_msg_manual_control_send(_channel,
mavlink_system.sysid,
- manual->roll * 1000,
- manual->pitch * 1000,
- manual->yaw * 1000,
- manual->throttle * 1000,
+ manual->x * 1000,
+ manual->y * 1000,
+ manual->z * 1000,
+ manual->r * 1000,
0);
}
}
@@ -1339,22 +1343,23 @@ protected:
void send(const hrt_abstime t)
{
- (void)range_sub->update(t);
+ if (range_sub->update(t)) {
- uint8_t type;
+ uint8_t type;
- switch (range->type) {
- case RANGE_FINDER_TYPE_LASER:
- type = MAV_DISTANCE_SENSOR_LASER;
- break;
- }
+ switch (range->type) {
+ case RANGE_FINDER_TYPE_LASER:
+ type = MAV_DISTANCE_SENSOR_LASER;
+ break;
+ }
- uint8_t id = 0;
- uint8_t orientation = 0;
- uint8_t covariance = 20;
+ uint8_t id = 0;
+ 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);
+ }
}
};
diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp
index d432edd2b..21d5219d3 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.cpp
+++ b/src/modules/mavlink/mavlink_orb_subscription.cpp
@@ -63,7 +63,7 @@ MavlinkOrbSubscription::~MavlinkOrbSubscription()
free(_data);
}
-const orb_id_t
+orb_id_t
MavlinkOrbSubscription::get_topic()
{
return _topic;
diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h
index 5c6543e81..8c09772c8 100644
--- a/src/modules/mavlink/mavlink_orb_subscription.h
+++ b/src/modules/mavlink/mavlink_orb_subscription.h
@@ -63,7 +63,7 @@ public:
*/
bool is_published();
void *get_data();
- const orb_id_t get_topic();
+ orb_id_t get_topic();
private:
const orb_id_t _topic; /*< topic metadata */
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 33a4fef12..53769e0cf 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -191,7 +191,7 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
}
}
-
+
/* If we've received a valid message, mark the flag indicating so.
This is used in the '-w' command-line flag. */
_mavlink->set_has_received_messages(true);
@@ -217,6 +217,12 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
_mavlink->_task_should_exit = true;
} else {
+
+ if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) {
+ warnx("ignoring CMD spoofed with same SYS/COMP ID");
+ return;
+ }
+
struct vehicle_command_s vcmd;
memset(&vcmd, 0, sizeof(vcmd));
@@ -432,10 +438,10 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
memset(&manual, 0, sizeof(manual));
manual.timestamp = hrt_absolute_time();
- manual.roll = man.x / 1000.0f;
- manual.pitch = man.y / 1000.0f;
- manual.yaw = man.r / 1000.0f;
- manual.throttle = man.z / 1000.0f;
+ manual.x = man.x / 1000.0f;
+ manual.y = man.y / 1000.0f;
+ manual.r = man.r / 1000.0f;
+ manual.z = man.z / 1000.0f;
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
@@ -926,6 +932,8 @@ void *MavlinkReceiver::start_helper(void *context)
rcv->receive_thread(NULL);
delete rcv;
+
+ return nullptr;
}
pthread_t
@@ -943,7 +951,7 @@ MavlinkReceiver::receive_start(Mavlink *parent)
param.sched_priority = SCHED_PRIORITY_MAX - 40;
(void)pthread_attr_setschedparam(&receiveloop_attr, &param);
- pthread_attr_setstacksize(&receiveloop_attr, 3000);
+ pthread_attr_setstacksize(&receiveloop_attr, 2900);
pthread_t thread;
pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent);
diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp
index bb19d7e33..5ec30bd33 100644
--- a/src/modules/mavlink/mavlink_stream.cpp
+++ b/src/modules/mavlink/mavlink_stream.cpp
@@ -81,5 +81,9 @@ MavlinkStream::update(const hrt_abstime t)
/* interval expired, send message */
send(t);
_last_sent = (t / _interval) * _interval;
+
+ return 0;
}
+
+ return -1;
}
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index def40d9ad..2979d20de 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -63,9 +63,13 @@ public:
MavlinkStream *next;
MavlinkStream();
- ~MavlinkStream();
+ virtual ~MavlinkStream();
void set_interval(const unsigned int interval);
void set_channel(mavlink_channel_t channel);
+
+ /**
+ * @return 0 if updated / sent, -1 if unchanged
+ */
int update(const hrt_abstime t);
virtual MavlinkStream *new_instance() = 0;
virtual void subscribe(Mavlink *mavlink) = 0;
diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk
index dcca11977..f532e26fe 100644
--- a/src/modules/mavlink/module.mk
+++ b/src/modules/mavlink/module.mk
@@ -48,3 +48,5 @@ SRCS += mavlink_main.cpp \
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1024
diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp
index 6b0c44fb3..20e016da3 100644
--- a/src/modules/mc_att_control/mc_att_control_main.cpp
+++ b/src/modules/mc_att_control/mc_att_control_main.cpp
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,9 +32,13 @@
****************************************************************************/
/**
- * @file mc_att_control_main.c
+ * @file mc_att_control_main.cpp
* Multicopter attitude controller.
*
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ *
* The controller has two loops: P loop for angular error and PD loop for angular rate error.
* Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch.
* For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw,
@@ -71,7 +72,7 @@
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <systemlib/systemlib.h>
-#include <mathlib/mathlib.h>
+#include <lib/mathlib/mathlib.h>
#include <lib/geo/geo.h>
/**
@@ -156,10 +157,14 @@ private:
param_t yaw_rate_i;
param_t yaw_rate_d;
param_t yaw_ff;
+ param_t yaw_rate_max;
param_t man_roll_max;
param_t man_pitch_max;
param_t man_yaw_max;
+ param_t acro_roll_max;
+ param_t acro_pitch_max;
+ param_t acro_yaw_max;
} _params_handles; /**< handles for interesting parameters */
struct {
@@ -168,10 +173,12 @@ private:
math::Vector<3> rate_i; /**< I gain for angular rate error */
math::Vector<3> rate_d; /**< D gain for angular rate error */
float yaw_ff; /**< yaw control feed-forward */
+ float yaw_rate_max; /**< max yaw rate */
float man_roll_max;
float man_pitch_max;
float man_yaw_max;
+ math::Vector<3> acro_rate_max; /**< max attitude rates in acro mode */
} _params;
/**
@@ -225,9 +232,9 @@ private:
static void task_main_trampoline(int argc, char *argv[]);
/**
- * Main sensor collection task.
+ * Main attitude control task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace mc_att_control
@@ -276,6 +283,12 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params.rate_p.zero();
_params.rate_i.zero();
_params.rate_d.zero();
+ _params.yaw_ff = 0.0f;
+ _params.yaw_rate_max = 0.0f;
+ _params.man_roll_max = 0.0f;
+ _params.man_pitch_max = 0.0f;
+ _params.man_yaw_max = 0.0f;
+ _params.acro_rate_max.zero();
_rates_prev.zero();
_rates_sp.zero();
@@ -298,10 +311,13 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() :
_params_handles.yaw_rate_i = param_find("MC_YAWRATE_I");
_params_handles.yaw_rate_d = param_find("MC_YAWRATE_D");
_params_handles.yaw_ff = param_find("MC_YAW_FF");
-
+ _params_handles.yaw_rate_max = param_find("MC_YAWRATE_MAX");
_params_handles.man_roll_max = param_find("MC_MAN_R_MAX");
_params_handles.man_pitch_max = param_find("MC_MAN_P_MAX");
_params_handles.man_yaw_max = param_find("MC_MAN_Y_MAX");
+ _params_handles.acro_roll_max = param_find("MC_ACRO_R_MAX");
+ _params_handles.acro_pitch_max = param_find("MC_ACRO_P_MAX");
+ _params_handles.acro_yaw_max = param_find("MC_ACRO_Y_MAX");
/* fetch initial parameter values */
parameters_update();
@@ -367,15 +383,24 @@ MulticopterAttitudeControl::parameters_update()
_params.rate_d(2) = v;
param_get(_params_handles.yaw_ff, &_params.yaw_ff);
+ param_get(_params_handles.yaw_rate_max, &_params.yaw_rate_max);
+ _params.yaw_rate_max = math::radians(_params.yaw_rate_max);
/* manual control scale */
param_get(_params_handles.man_roll_max, &_params.man_roll_max);
param_get(_params_handles.man_pitch_max, &_params.man_pitch_max);
param_get(_params_handles.man_yaw_max, &_params.man_yaw_max);
-
- _params.man_roll_max *= M_PI / 180.0;
- _params.man_pitch_max *= M_PI / 180.0;
- _params.man_yaw_max *= M_PI / 180.0;
+ _params.man_roll_max = math::radians(_params.man_roll_max);
+ _params.man_pitch_max = math::radians(_params.man_pitch_max);
+ _params.man_yaw_max = math::radians(_params.man_yaw_max);
+
+ /* acro control scale */
+ param_get(_params_handles.acro_roll_max, &v);
+ _params.acro_rate_max(0) = math::radians(v);
+ param_get(_params_handles.acro_pitch_max, &v);
+ _params.acro_rate_max(1) = math::radians(v);
+ param_get(_params_handles.acro_yaw_max, &v);
+ _params.acro_rate_max(2) = math::radians(v);
return OK;
}
@@ -478,7 +503,7 @@ MulticopterAttitudeControl::control_attitude(float dt)
if (!_v_control_mode.flag_control_climb_rate_enabled) {
/* pass throttle directly if not in altitude stabilized mode */
- _v_att_sp.thrust = _manual_control_sp.throttle;
+ _v_att_sp.thrust = _manual_control_sp.z;
publish_att_sp = true;
}
@@ -496,7 +521,16 @@ MulticopterAttitudeControl::control_attitude(float dt)
//}
} else {
/* move yaw setpoint */
- _v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + _manual_control_sp.yaw * _params.man_yaw_max * dt);
+ yaw_sp_move_rate = _manual_control_sp.r * _params.man_yaw_max;
+ _v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + yaw_sp_move_rate * dt);
+ float yaw_offs_max = _params.man_yaw_max / _params.att_p(2);
+ float yaw_offs = _wrap_pi(_v_att_sp.yaw_body - _v_att.yaw);
+ if (yaw_offs < - yaw_offs_max) {
+ _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw - yaw_offs_max);
+
+ } else if (yaw_offs > yaw_offs_max) {
+ _v_att_sp.yaw_body = _wrap_pi(_v_att.yaw + yaw_offs_max);
+ }
_v_att_sp.R_valid = false;
publish_att_sp = true;
}
@@ -511,8 +545,8 @@ MulticopterAttitudeControl::control_attitude(float dt)
if (!_v_control_mode.flag_control_velocity_enabled) {
/* update attitude setpoint if not in position control mode */
- _v_att_sp.roll_body = _manual_control_sp.roll * _params.man_roll_max;
- _v_att_sp.pitch_body = -_manual_control_sp.pitch * _params.man_pitch_max;
+ _v_att_sp.roll_body = _manual_control_sp.y * _params.man_roll_max;
+ _v_att_sp.pitch_body = -_manual_control_sp.x * _params.man_pitch_max;
_v_att_sp.R_valid = false;
publish_att_sp = true;
}
@@ -625,6 +659,9 @@ MulticopterAttitudeControl::control_attitude(float dt)
/* calculate angular rates setpoint */
_rates_sp = _params.att_p.emult(e_R);
+ /* limit yaw rate */
+ _rates_sp(2) = math::constrain(_rates_sp(2), -_params.yaw_rate_max, _params.yaw_rate_max);
+
/* feed forward yaw setpoint rate */
_rates_sp(2) += yaw_sp_move_rate * yaw_w * _params.yaw_ff;
}
@@ -761,11 +798,36 @@ MulticopterAttitudeControl::task_main()
} else {
/* attitude controller disabled, poll rates setpoint topic */
- vehicle_rates_setpoint_poll();
- _rates_sp(0) = _v_rates_sp.roll;
- _rates_sp(1) = _v_rates_sp.pitch;
- _rates_sp(2) = _v_rates_sp.yaw;
- _thrust_sp = _v_rates_sp.thrust;
+ if (_v_control_mode.flag_control_manual_enabled) {
+ /* manual rates control - ACRO mode */
+ _rates_sp = math::Vector<3>(_manual_control_sp.y, -_manual_control_sp.x, _manual_control_sp.r).emult(_params.acro_rate_max);
+ _thrust_sp = _manual_control_sp.z;
+
+ /* reset yaw setpoint after ACRO */
+ _reset_yaw_sp = true;
+
+ /* publish attitude rates setpoint */
+ _v_rates_sp.roll = _rates_sp(0);
+ _v_rates_sp.pitch = _rates_sp(1);
+ _v_rates_sp.yaw = _rates_sp(2);
+ _v_rates_sp.thrust = _thrust_sp;
+ _v_rates_sp.timestamp = hrt_absolute_time();
+
+ if (_v_rates_sp_pub > 0) {
+ orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp);
+
+ } else {
+ _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp);
+ }
+
+ } else {
+ /* attitude controller disabled, poll rates setpoint topic */
+ vehicle_rates_setpoint_poll();
+ _rates_sp(0) = _v_rates_sp.roll;
+ _rates_sp(1) = _v_rates_sp.pitch;
+ _rates_sp(2) = _v_rates_sp.yaw;
+ _thrust_sp = _v_rates_sp.thrust;
+ }
}
if (_v_control_mode.flag_control_rates_enabled) {
@@ -805,7 +867,7 @@ MulticopterAttitudeControl::start()
_control_task = task_spawn_cmd("mc_att_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&MulticopterAttitudeControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c
index e52c39368..819847b40 100644
--- a/src/modules/mc_att_control/mc_att_control_params.c
+++ b/src/modules/mc_att_control/mc_att_control_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -37,6 +34,10 @@
/**
* @file mc_att_control_params.c
* Parameters for multicopter attitude controller.
+ *
+ * @author Tobias Naegeli <naegelit@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <systemlib/param/param.h>
@@ -175,6 +176,18 @@ PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f);
PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f);
/**
+ * Max yaw rate
+ *
+ * Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_YAWRATE_MAX, 120.0f);
+
+/**
* Max manual roll
*
* @unit deg
@@ -202,3 +215,32 @@ PARAM_DEFINE_FLOAT(MC_MAN_P_MAX, 35.0f);
* @group Multicopter Attitude Control
*/
PARAM_DEFINE_FLOAT(MC_MAN_Y_MAX, 120.0f);
+
+/**
+ * Max acro roll rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_R_MAX, 90.0f);
+
+/**
+ * Max acro pitch rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @max 360.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_P_MAX, 90.0f);
+
+/**
+ * Max acro yaw rate
+ *
+ * @unit deg/s
+ * @min 0.0
+ * @group Multicopter Attitude Control
+ */
+PARAM_DEFINE_FLOAT(MC_ACRO_Y_MAX, 120.0f);
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index 7c625a0c5..09960d106 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -226,7 +226,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace pos_control
@@ -617,7 +617,7 @@ MulticopterPositionControl::task_main()
reset_alt_sp();
/* move altitude setpoint with throttle stick */
- sp_move_rate(2) = -scale_control(_manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
+ sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz);
}
if (_control_mode.flag_control_position_enabled) {
@@ -625,8 +625,8 @@ MulticopterPositionControl::task_main()
reset_pos_sp();
/* move position setpoint with roll/pitch stick */
- sp_move_rate(0) = _manual.pitch;
- sp_move_rate(1) = _manual.roll;
+ sp_move_rate(0) = _manual.x;
+ sp_move_rate(1) = _manual.y;
}
/* limit setpoint move rate */
@@ -782,7 +782,7 @@ MulticopterPositionControl::task_main()
float i = _params.thr_min;
if (reset_int_z_manual) {
- i = _manual.throttle;
+ i = _manual.z;
if (i < _params.thr_min) {
i = _params.thr_min;
@@ -1062,7 +1062,7 @@ MulticopterPositionControl::start()
_control_task = task_spawn_cmd("mc_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&MulticopterPositionControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c
index 104df4e59..05ab5769b 100644
--- a/src/modules/mc_pos_control/mc_pos_control_params.c
+++ b/src/modules/mc_pos_control/mc_pos_control_params.c
@@ -35,6 +35,8 @@
/**
* @file mc_pos_control_params.c
* Multicopter position controller parameters.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <systemlib/param/param.h>
@@ -98,7 +100,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f);
/**
* Maximum vertical velocity
*
- * Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY).
+ * Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).
*
* @unit m/s
* @min 0.0
@@ -109,7 +111,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f);
/**
* Vertical velocity feed forward
*
- * Feed forward weight for altitude control in stabilized modes (SEATBELT, EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ * Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
@@ -154,7 +156,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f);
/**
* Maximum horizontal velocity
*
- * Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY).
+ * Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).
*
* @unit m/s
* @min 0.0
@@ -165,7 +167,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
/**
* Horizontal velocity feed forward
*
- * Feed forward weight for position control in position control mode (EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ * Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
*
* @min 0.0
* @max 1.0
@@ -176,7 +178,7 @@ PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
/**
* Maximum tilt angle in air
*
- * Limits maximum tilt in AUTO and EASY modes during flight.
+ * Limits maximum tilt in AUTO and POSCTRL modes during flight.
*
* @unit deg
* @min 0.0
diff --git a/src/modules/navigator/geofence.cpp b/src/modules/navigator/geofence.cpp
index f452a85f7..bc8dbca50 100644
--- a/src/modules/navigator/geofence.cpp
+++ b/src/modules/navigator/geofence.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file geofence.cpp
* Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#include "geofence.h"
diff --git a/src/modules/navigator/geofence.h b/src/modules/navigator/geofence.h
index 9628b7271..2eb126ab5 100644
--- a/src/modules/navigator/geofence.h
+++ b/src/modules/navigator/geofence.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file geofence.h
* Provides functions for handling the geofence
+ *
+ * @author Jean Cyr <jean.m.cyr@gmail.com>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*/
#ifndef GEOFENCE_H_
diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c
index 5831a0ca9..653b1ad84 100644
--- a/src/modules/navigator/geofence_params.c
+++ b/src/modules/navigator/geofence_params.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * 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
diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp
index eaafa217d..e1a6854b2 100644
--- a/src/modules/navigator/mission_feasibility_checker.cpp
+++ b/src/modules/navigator/mission_feasibility_checker.cpp
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,6 +33,9 @@
/**
* @file mission_feasibility_checker.cpp
* Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
#include "mission_feasibility_checker.h"
@@ -62,7 +63,7 @@ MissionFeasibilityChecker::MissionFeasibilityChecker() : _mavlink_fd(-1), _capab
}
-bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Init if not done yet */
init();
@@ -75,24 +76,24 @@ bool MissionFeasibilityChecker::checkMissionFeasible(bool isRotarywing, dm_item_
if (isRotarywing)
- return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence);
+ return checkMissionFeasibleRotarywing(dm_current, nMissionItems, geofence, home_alt);
else
- return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence);
+ return checkMissionFeasibleFixedwing(dm_current, nMissionItems, geofence, home_alt);
}
-bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
- return checkGeofence(dm_current, nMissionItems, geofence);
+ return (checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
-bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
+bool MissionFeasibilityChecker::checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt)
{
/* Update fixed wing navigation capabilites */
updateNavigationCapabilities();
// warnx("_nav_caps.landing_slope_angle_rad %.4f, _nav_caps.landing_horizontal_slope_displacement %.4f", _nav_caps.landing_slope_angle_rad, _nav_caps.landing_horizontal_slope_displacement);
- return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence));
+ return (checkFixedWingLanding(dm_current, nMissionItems) && checkGeofence(dm_current, nMissionItems, geofence) && checkHomePositionAltitude(dm_current, nMissionItems, home_alt));
}
bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence)
@@ -100,15 +101,15 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
/* Check if all mission items are inside the geofence (if we have a valid geofence) */
if (geofence.valid()) {
for (size_t i = 0; i < nMissionItems; i++) {
- static struct mission_item_s missionitem;
- const ssize_t len = sizeof(struct mission_item_s);
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
return false;
}
- if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) { //xxx: handle relative altitude
+ if (!geofence.inside(missionitem.lat, missionitem.lon, missionitem.altitude)) {
mavlink_log_info(_mavlink_fd, "#audio: Geofence violation waypoint %d", i);
return false;
}
@@ -118,6 +119,36 @@ bool MissionFeasibilityChecker::checkGeofence(dm_item_t dm_current, size_t nMiss
return true;
}
+bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error)
+{
+ /* Check if all all waypoints are above the home altitude, only return false if bool throw_error = true */
+ for (size_t i = 0; i < nMissionItems; i++) {
+ static struct mission_item_s missionitem;
+ const ssize_t len = sizeof(struct mission_item_s);
+
+ if (dm_read(dm_current, i, &missionitem, len) != len) {
+ /* not supposed to happen unless the datamanager can't access the SD card, etc. */
+ if (throw_error) {
+ return false;
+ } else {
+ return true;
+ }
+ }
+
+ if (home_alt > missionitem.altitude) {
+ if (throw_error) {
+ mavlink_log_info(_mavlink_fd, "Waypoint %d below home", i);
+ return false;
+ } else {
+ mavlink_log_info(_mavlink_fd, "#audio: warning waypoint %d below home", i);
+ return true;
+ }
+ }
+ }
+
+ return true;
+}
+
bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems)
{
/* Go through all mission items and search for a landing waypoint
@@ -125,8 +156,8 @@ bool MissionFeasibilityChecker::checkFixedWingLanding(dm_item_t dm_current, size
for (size_t i = 0; i < nMissionItems; i++) {
- static struct mission_item_s missionitem;
- const ssize_t len = sizeof(struct mission_item_s);
+ struct mission_item_s missionitem;
+ const ssize_t len = sizeof(missionitem);
if (dm_read(dm_current, i, &missionitem, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
return false;
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
index 7a0b2a296..96c9209d3 100644
--- a/src/modules/navigator/mission_feasibility_checker.h
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -1,8 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +33,11 @@
/**
* @file mission_feasibility_checker.h
* Provides checks if mission is feasible given the navigation capabilities
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
*/
+
#ifndef MISSION_FEASIBILITY_CHECKER_H_
#define MISSION_FEASIBILITY_CHECKER_H_
@@ -59,14 +61,15 @@ private:
/* Checks for all airframes */
bool checkGeofence(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkHomePositionAltitude(dm_item_t dm_current, size_t nMissionItems, float home_alt, bool throw_error = false);
/* Checks specific to fixedwing airframes */
- bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasibleFixedwing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
bool checkFixedWingLanding(dm_item_t dm_current, size_t nMissionItems);
void updateNavigationCapabilities();
/* Checks specific to rotarywing airframes */
- bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasibleRotarywing(dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
public:
MissionFeasibilityChecker();
@@ -75,7 +78,7 @@ public:
/*
* Returns true if mission is feasible and false otherwise
*/
- bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence);
+ bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
};
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index 55f8a4caa..6ea9dec2b 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -45,3 +45,5 @@ SRCS = navigator_main.cpp \
geofence_params.c
INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 12fd35a0a..401d50f7e 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -1,10 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Jean Cyr <jean.m.cyr@gmail.com>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +31,7 @@
*
****************************************************************************/
/**
- * @file navigator_main.c
+ * @file navigator_main.cpp
* Implementation of the main navigation state machine.
*
* Handles missions, geo fencing and failsafe navigation behavior.
@@ -523,7 +519,7 @@ Navigator::offboard_mission_update(bool isrotaryWing)
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
- missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence);
+ missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence, _home_pos.alt);
_mission.set_offboard_dataman_id(offboard_mission.dataman_id);
@@ -852,7 +848,7 @@ Navigator::start()
_navigator_task = task_spawn_cmd("navigator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&Navigator::task_main_trampoline,
nullptr);
@@ -1291,7 +1287,7 @@ Navigator::set_rtl_item()
_mission_item.yaw = NAN;
_mission_item.loiter_radius = _parameters.loiter_radius;
_mission_item.loiter_direction = 1;
- _mission_item.nav_cmd = NAV_CMD_TAKEOFF;
+ _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;
@@ -1351,7 +1347,7 @@ Navigator::set_rtl_item()
_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.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;
diff --git a/src/modules/navigator/navigator_mission.cpp b/src/modules/navigator/navigator_mission.cpp
index 72dddebfe..49fc62785 100644
--- a/src/modules/navigator/navigator_mission.cpp
+++ b/src/modules/navigator/navigator_mission.cpp
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +33,8 @@
/**
* @file navigator_mission.cpp
* Helper class to access missions
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#include <string.h>
diff --git a/src/modules/navigator/navigator_mission.h b/src/modules/navigator/navigator_mission.h
index 2bd4da82e..b0f88e016 100644
--- a/src/modules/navigator/navigator_mission.h
+++ b/src/modules/navigator/navigator_mission.h
@@ -1,7 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Julian Oes <joes@student.ethz.ch>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,6 +33,8 @@
/**
* @file navigator_mission.h
* Helper class to access missions
+ *
+ * @author Julian Oes <joes@student.ethz.ch>
*/
#ifndef NAVIGATOR_MISSION_H
diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c
index 9ef359c6d..5139283b6 100644
--- a/src/modules/navigator/navigator_params.c
+++ b/src/modules/navigator/navigator_params.c
@@ -1,9 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Julian Oes <joes@student.ethz.ch>
- * @author Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/src/modules/navigator/navigator_state.h b/src/modules/navigator/navigator_state.h
index 6a1475c9b..476f93414 100644
--- a/src/modules/navigator/navigator_state.h
+++ b/src/modules/navigator/navigator_state.h
@@ -1,8 +1,42 @@
-/*
- * navigator_state.h
+/****************************************************************************
*
- * Created on: 27.01.2014
- * Author: ton
+ * 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_state.h
+ *
+ * Navigator state
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef NAVIGATOR_STATE_H_
diff --git a/src/modules/position_estimator/module.mk b/src/modules/position_estimator/module.mk
deleted file mode 100644
index f64095d9d..000000000
--- a/src/modules/position_estimator/module.mk
+++ /dev/null
@@ -1,44 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Makefile to build the position estimator
-#
-
-MODULE_COMMAND = position_estimator
-
-# XXX this should be converted to a deamon, its a pretty bad example app
-MODULE_PRIORITY = SCHED_PRIORITY_DEFAULT
-MODULE_STACKSIZE = 4096
-
-SRCS = position_estimator_main.c
diff --git a/src/modules/position_estimator/position_estimator_main.c b/src/modules/position_estimator/position_estimator_main.c
deleted file mode 100644
index e84945299..000000000
--- a/src/modules/position_estimator/position_estimator_main.c
+++ /dev/null
@@ -1,423 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Thomas Gubler <thomasgubler@student.ethz.ch>
- * Julian Oes <joes@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file position_estimator_main.c
- * Model-identification based position estimator for multirotors
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <stdbool.h>
-#include <fcntl.h>
-#include <float.h>
-#include <nuttx/sched.h>
-#include <sys/prctl.h>
-#include <termios.h>
-#include <errno.h>
-#include <limits.h>
-#include <math.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <poll.h>
-
-#define N_STATES 6
-#define ERROR_COVARIANCE_INIT 3
-#define R_EARTH 6371000.0
-
-#define PROJECTION_INITIALIZE_COUNTER_LIMIT 5000
-#define REPROJECTION_COUNTER_LIMIT 125
-
-__EXPORT int position_estimator_main(int argc, char *argv[]);
-
-static uint16_t position_estimator_counter_position_information;
-
-/* values for map projection */
-static double phi_1;
-static double sin_phi_1;
-static double cos_phi_1;
-static double lambda_0;
-static double scale;
-
-/**
- * Initializes the map transformation.
- *
- * Initializes the transformation between the geographic coordinate system and the azimuthal equidistant plane
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-static void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
-{
- /* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- phi_1 = lat_0 / 180.0 * M_PI;
- lambda_0 = lon_0 / 180.0 * M_PI;
-
- sin_phi_1 = sin(phi_1);
- cos_phi_1 = cos(phi_1);
-
- /* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
-
- /* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
- const double r_earth = 6371000;
-
- double lat1 = phi_1;
- double lon1 = lambda_0;
-
- double lat2 = phi_1 + 0.5 / 180 * M_PI;
- double lon2 = lambda_0 + 0.5 / 180 * M_PI;
- double sin_lat_2 = sin(lat2);
- double cos_lat_2 = cos(lat2);
- double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * r_earth;
-
- /* 2) calculate distance rho on plane */
- double k_bar = 0;
- double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
-
- if (0 != c)
- k_bar = c / sin(c);
-
- double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
- double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
- double rho = sqrt(pow(x2, 2) + pow(y2, 2));
-
- scale = d / rho;
-
-}
-
-/**
- * Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-static void map_projection_project(double lat, double lon, float *x, float *y)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
- double phi = lat / 180.0 * M_PI;
- double lambda = lon / 180.0 * M_PI;
-
- double sin_phi = sin(phi);
- double cos_phi = cos(phi);
-
- double k_bar = 0;
- /* using small angle approximation (formula in comment is without aproximation) */
- double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
-
- if (0 != c)
- k_bar = c / sin(c);
-
- /* using small angle approximation (formula in comment is without aproximation) */
- *y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
- *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
-
-// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
-}
-
-/**
- * Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
- *
- * @param x north
- * @param y east
- * @param lat in degrees (47.1234567°, not 471234567°)
- * @param lon in degrees (8.1234567°, not 81234567°)
- */
-static void map_projection_reproject(float x, float y, double *lat, double *lon)
-{
- /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
-
- double x_descaled = x / scale;
- double y_descaled = y / scale;
-
- double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
- double sin_c = sin(c);
- double cos_c = cos(c);
-
- double lat_sphere = 0;
-
- if (c != 0)
- lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
- else
- lat_sphere = asin(cos_c * sin_phi_1);
-
-// printf("lat_sphere = %.10f\n",lat_sphere);
-
- double lon_sphere = 0;
-
- if (phi_1 == M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
-
- } else if (phi_1 == -M_PI / 2) {
- //using small angle approximation (formula in comment is without aproximation)
- lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
-
- } else {
-
- lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
- //using small angle approximation
-// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
-// if(denominator != 0)
-// {
-// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
-// }
-// else
-// {
-// ...
-// }
- }
-
-// printf("lon_sphere = %.10f\n",lon_sphere);
-
- *lat = lat_sphere * 180.0 / M_PI;
- *lon = lon_sphere * 180.0 / M_PI;
-
-}
-
-/****************************************************************************
- * main
- ****************************************************************************/
-
-int position_estimator_main(int argc, char *argv[])
-{
-
- /* welcome user */
- printf("[multirotor position_estimator] started\n");
-
- /* initialize values */
- static float u[2] = {0, 0};
- static float z[3] = {0, 0, 0};
- static float xapo[N_STATES] = {0, 0, 0, 0, 0, 0};
- static float Papo[N_STATES * N_STATES] = {ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
- ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
- ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
- ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
- ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0,
- ERROR_COVARIANCE_INIT, 0, 0, 0, 0, 0
- };
-
- static float xapo1[N_STATES];
- static float Papo1[36];
-
- static float gps_covariance[3] = {0.0f, 0.0f, 0.0f};
-
- static uint16_t counter = 0;
- position_estimator_counter_position_information = 0;
-
- uint8_t predict_only = 1;
-
- bool gps_valid = false;
-
- bool new_initialization = true;
-
- static double lat_current = 0.0d;//[°]] --> 47.0
- static double lon_current = 0.0d; //[°]] -->8.5
- float alt_current = 0.0f;
-
-
- //TODO: handle flight without gps but with estimator
-
- /* subscribe to vehicle status, attitude, gps */
- struct vehicle_gps_position_s gps;
- gps.fix_type = 0;
- struct vehicle_status_s vstatus;
- struct vehicle_attitude_s att;
-
- int vehicle_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
-
- /* subscribe to attitude at 100 Hz */
- int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
-
- /* wait until gps signal turns valid, only then can we initialize the projection */
- while (gps.fix_type < 3) {
- struct pollfd fds[1] = { {.fd = vehicle_gps_sub, .events = POLLIN} };
-
- /* wait for GPS updates, BUT READ VEHICLE STATUS (!)
- * this choice is critical, since the vehicle status might not
- * actually change, if this app is started after GPS lock was
- * aquired.
- */
- if (poll(fds, 1, 5000)) {
- /* Wait for the GPS update to propagate (we have some time) */
- usleep(5000);
- /* Read wether the vehicle status changed */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- gps_valid = (gps.fix_type > 2);
- }
- }
-
- /* get gps value for first initialization */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- lat_current = ((double)(gps.lat)) * 1e-7;
- lon_current = ((double)(gps.lon)) * 1e-7;
- alt_current = gps.alt * 1e-3;
-
- /* initialize coordinates */
- map_projection_init(lat_current, lon_current);
-
- /* publish global position messages only after first GPS message */
- struct vehicle_local_position_s local_pos = {
- .x = 0,
- .y = 0,
- .z = 0
- };
- orb_advert_t local_pos_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos);
-
- printf("[multirotor position estimator] initialized projection with: lat: %.10f, lon:%.10f\n", lat_current, lon_current);
-
- while (1) {
-
- /*This runs at the rate of the sensors, if we have also a new gps update this is used in the position_estimator function */
- struct pollfd fds[1] = { {.fd = vehicle_attitude_sub, .events = POLLIN} };
-
- if (poll(fds, 1, 5000) <= 0) {
- /* error / timeout */
- } else {
-
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- /* got attitude, updating pos as well */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vstatus);
-
- /*copy attitude */
- u[0] = att.roll;
- u[1] = att.pitch;
-
- /* initialize map projection with the last estimate (not at full rate) */
- if (gps.fix_type > 2) {
- /* Project gps lat lon (Geographic coordinate system) to plane*/
- map_projection_project(((double)(gps.lat)) * 1e-7, ((double)(gps.lon)) * 1e-7, &(z[0]), &(z[1]));
-
- local_pos.x = z[0];
- local_pos.y = z[1];
- /* negative offset from initialization altitude */
- local_pos.z = alt_current - (gps.alt) * 1e-3;
-
-
- orb_publish(ORB_ID(vehicle_local_position), local_pos_pub, &local_pos);
- }
-
-
- // gps_covariance[0] = gps.eph; //TODO: needs scaling
- // gps_covariance[1] = gps.eph;
- // gps_covariance[2] = gps.epv;
-
- // } else {
- // /* we can not use the gps signal (it is of low quality) */
- // predict_only = 1;
- // }
-
- // // predict_only = 0; //TODO: only for testing, removeme, XXX
- // // z[0] = sinf(((float)counter)/180.0f*3.14159265f); //TODO: only for testing, removeme, XXX
- // // usleep(100000); //TODO: only for testing, removeme, XXX
-
-
- // /*Get new estimation (this is calculated in the plane) */
- // //TODO: if new_initialization == true: use 0,0,0, else use xapo
- // if (true == new_initialization) { //TODO,XXX: uncomment!
- // xapo[0] = 0; //we have a new plane initialization. the current estimate is in the center of the plane
- // xapo[2] = 0;
- // xapo[4] = 0;
- // position_estimator(u, z, xapo, Papo, gps_covariance, predict_only, xapo1, Papo1);
-
- // } else {
- // position_estimator(u, z, xapo, Papo, gps_covariance, predict_only, xapo1, Papo1);
- // }
-
-
-
- // /* Copy values from xapo1 to xapo */
- // int i;
-
- // for (i = 0; i < N_STATES; i++) {
- // xapo[i] = xapo1[i];
- // }
-
- // if ((counter % REPROJECTION_COUNTER_LIMIT == 0) || (counter % (PROJECTION_INITIALIZE_COUNTER_LIMIT - 1) == 0)) {
- // /* Reproject from plane to geographic coordinate system */
- // // map_projection_reproject(xapo1[0], xapo1[2], map_scale, phi_1, lambda_0, &lat_current, &lon_current) //TODO,XXX: uncomment!
- // map_projection_reproject(z[0], z[1], &lat_current, &lon_current); //do not use estimator for projection testing, removeme
- // // //DEBUG
- // // if(counter%500 == 0)
- // // {
- // // printf("phi_1: %.10f\n", phi_1);
- // // printf("lambda_0: %.10f\n", lambda_0);
- // // printf("lat_estimated: %.10f\n", lat_current);
- // // printf("lon_estimated: %.10f\n", lon_current);
- // // printf("z[0]=%.10f, z[1]=%.10f, z[2]=%f\n", z[0], z[1], z[2]);
- // // fflush(stdout);
- // //
- // // }
-
- // // if(!isnan(lat_current) && !isnan(lon_current))// && !isnan(xapo1[4]) && !isnan(xapo1[1]) && !isnan(xapo1[3]) && !isnan(xapo1[5]))
- // // {
- // /* send out */
-
- // global_pos.lat = lat_current;
- // global_pos.lon = lon_current;
- // global_pos.alt = xapo1[4];
- // global_pos.vx = xapo1[1];
- // global_pos.vy = xapo1[3];
- // global_pos.vz = xapo1[5];
-
- /* publish current estimate */
- // orb_publish(ORB_ID(vehicle_global_position), global_pos_pub, &global_pos);
- // }
- // else
- // {
- // printf("[position estimator] ERROR: nan values, lat_current=%.4f, lon_current=%.4f, z[0]=%.4f z[1]=%.4f\n", lat_current, lon_current, z[0], z[1]);
- // fflush(stdout);
- // }
-
- // }
-
- counter++;
- }
-
- }
-
- return 0;
-}
-
-
diff --git a/src/modules/position_estimator_inav/inertial_filter.c b/src/modules/position_estimator_inav/inertial_filter.c
index 2f1b3c014..a36a4688d 100644
--- a/src/modules/position_estimator_inav/inertial_filter.c
+++ b/src/modules/position_estimator_inav/inertial_filter.c
@@ -9,15 +9,18 @@
#include "inertial_filter.h"
-void inertial_filter_predict(float dt, float x[3])
+void inertial_filter_predict(float dt, float x[2], float acc)
{
if (isfinite(dt)) {
- x[0] += x[1] * dt + x[2] * dt * dt / 2.0f;
- x[1] += x[2] * dt;
+ if (!isfinite(acc)) {
+ acc = 0.0f;
+ }
+ x[0] += x[1] * dt + acc * dt * dt / 2.0f;
+ x[1] += acc * dt;
}
}
-void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
+void inertial_filter_correct(float e, float dt, float x[2], int i, float w)
{
if (isfinite(e) && isfinite(w) && isfinite(dt)) {
float ewdt = e * w * dt;
@@ -25,10 +28,6 @@ void inertial_filter_correct(float e, float dt, float x[3], int i, float w)
if (i == 0) {
x[1] += w * ewdt;
- x[2] += w * w * ewdt / 3.0;
-
- } else if (i == 1) {
- x[2] += w * ewdt;
}
}
}
diff --git a/src/modules/position_estimator_inav/inertial_filter.h b/src/modules/position_estimator_inav/inertial_filter.h
index 761c17097..cdeb4cfc6 100644
--- a/src/modules/position_estimator_inav/inertial_filter.h
+++ b/src/modules/position_estimator_inav/inertial_filter.h
@@ -8,6 +8,6 @@
#include <stdbool.h>
#include <drivers/drv_hrt.h>
-void inertial_filter_predict(float dt, float x[3]);
+void inertial_filter_predict(float dt, float x[3], float acc);
void inertial_filter_correct(float e, float dt, float x[3], int i, float w);
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
index 939d76849..0658d3f09 100644
--- a/src/modules/position_estimator_inav/module.mk
+++ b/src/modules/position_estimator_inav/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = position_estimator_inav
SRCS = position_estimator_inav_main.c \
position_estimator_inav_params.c \
inertial_filter.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 368424853..d7503e42d 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -135,7 +135,7 @@ int position_estimator_inav_main(int argc, char *argv[])
thread_should_exit = false;
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
- SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 4000,
position_estimator_inav_thread_main,
(argv) ? (const char **) &argv[2] : (const char **) NULL);
exit(0);
@@ -168,15 +168,15 @@ int position_estimator_inav_main(int argc, char *argv[])
exit(1);
}
-void write_debug_log(const char *msg, float dt, float x_est[3], float y_est[3], float z_est[3], float x_est_prev[3], float y_est_prev[3], float z_est_prev[3], float corr_acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
+void write_debug_log(const char *msg, float dt, float x_est[2], float y_est[2], float z_est[2], float x_est_prev[2], float y_est_prev[2], float z_est_prev[2], float acc[3], float corr_gps[3][2], float w_xy_gps_p, float w_xy_gps_v)
{
FILE *f = fopen("/fs/microsd/inav.log", "a");
if (f) {
char *s = malloc(256);
- unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f %.5f] y_est=[%.5f %.5f %.5f] z_est=[%.5f %.5f %.5f] x_est_prev=[%.5f %.5f %.5f] y_est_prev=[%.5f %.5f %.5f] z_est_prev=[%.5f %.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2], z_est[0], z_est[1], z_est[2], x_est_prev[0], x_est_prev[1], x_est_prev[2], y_est_prev[0], y_est_prev[1], y_est_prev[2], z_est_prev[0], z_est_prev[1], z_est_prev[2]);
+ unsigned n = snprintf(s, 256, "%llu %s\n\tdt=%.5f x_est=[%.5f %.5f] y_est=[%.5f %.5f] z_est=[%.5f %.5f] x_est_prev=[%.5f %.5f] y_est_prev=[%.5f %.5f] z_est_prev=[%.5f %.5f]\n", hrt_absolute_time(), msg, dt, x_est[0], x_est[1], y_est[0], y_est[1], z_est[0], z_est[1], x_est_prev[0], x_est_prev[1], y_est_prev[0], y_est_prev[1], z_est_prev[0], z_est_prev[1]);
fwrite(s, 1, n, f);
- n = snprintf(s, 256, "\tacc_corr=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", corr_acc[0], corr_acc[1], corr_acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v);
+ n = snprintf(s, 256, "\tacc=[%.5f %.5f %.5f] gps_pos_corr=[%.5f %.5f %.5f] gps_vel_corr=[%.5f %.5f %.5f] w_xy_gps_p=%.5f w_xy_gps_v=%.5f\n", acc[0], acc[1], acc[2], corr_gps[0][0], corr_gps[1][0], corr_gps[2][0], corr_gps[0][1], corr_gps[1][1], corr_gps[2][1], w_xy_gps_p, w_xy_gps_v);
fwrite(s, 1, n, f);
free(s);
}
@@ -195,11 +195,14 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
mavlink_log_info(mavlink_fd, "[inav] started");
- float x_est[3] = { 0.0f, 0.0f, 0.0f };
- float y_est[3] = { 0.0f, 0.0f, 0.0f };
- float z_est[3] = { 0.0f, 0.0f, 0.0f };
+ float x_est[2] = { 0.0f, 0.0f }; // pos, vel
+ float y_est[2] = { 0.0f, 0.0f }; // pos, vel
+ float z_est[2] = { 0.0f, 0.0f }; // pos, vel
- float x_est_prev[3], y_est_prev[3], z_est_prev[3];
+ float eph = 1.0;
+ float epv = 1.0;
+
+ float x_est_prev[2], y_est_prev[2], z_est_prev[2];
memset(x_est_prev, 0, sizeof(x_est_prev));
memset(y_est_prev, 0, sizeof(y_est_prev));
memset(z_est_prev, 0, sizeof(z_est_prev));
@@ -238,7 +241,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
/* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */
- float corr_acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
+ float acc[] = { 0.0f, 0.0f, 0.0f }; // N E D
float acc_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
float corr_baro = 0.0f; // D
float corr_gps[3][2] = {
@@ -338,8 +341,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
- baro_offset += sensor.baro_alt_meter;
- baro_init_cnt++;
+ if (isfinite(sensor.baro_alt_meter)) {
+ baro_offset += sensor.baro_alt_meter;
+ baro_init_cnt++;
+ }
} else {
wait_baro = false;
@@ -415,19 +420,17 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* transform acceleration vector from body frame to NED frame */
for (int i = 0; i < 3; i++) {
- accel_NED[i] = 0.0f;
+ acc[i] = 0.0f;
for (int j = 0; j < 3; j++) {
- accel_NED[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
+ acc[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
}
}
- corr_acc[0] = accel_NED[0] - x_est[2];
- corr_acc[1] = accel_NED[1] - y_est[2];
- corr_acc[2] = accel_NED[2] + CONSTANTS_ONE_G - z_est[2];
+ acc[2] += CONSTANTS_ONE_G;
} else {
- memset(corr_acc, 0, sizeof(corr_acc));
+ memset(acc, 0, sizeof(acc));
}
accel_timestamp = sensor.accelerometer_timestamp;
@@ -535,6 +538,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
flow_valid = true;
+ eph = fminf(eph, 0.1 / att.R[2][2] / flow_q * fmaxf(1.0f, flow_dist)); // under ideal conditions, on 1m distance assume EPH = 10cm
+
} else {
w_flow = 0.0f;
flow_valid = false;
@@ -623,11 +628,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* set position estimate to (0, 0, 0), use GPS velocity for XY */
x_est[0] = 0.0f;
x_est[1] = gps.vel_n_m_s;
- x_est[2] = accel_NED[0];
y_est[0] = 0.0f;
y_est[1] = gps.vel_e_m_s;
z_est[0] = 0.0f;
- y_est[2] = accel_NED[1];
local_pos.ref_lat = lat;
local_pos.ref_lon = lon;
@@ -650,10 +653,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (reset_est) {
x_est[0] = gps_proj[0];
x_est[1] = gps.vel_n_m_s;
- x_est[2] = accel_NED[0];
y_est[0] = gps_proj[1];
y_est[1] = gps.vel_e_m_s;
- y_est[2] = accel_NED[1];
}
/* calculate correction for position */
@@ -673,6 +674,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
corr_gps[2][1] = 0.0f;
}
+ eph = fminf(eph, gps.eph_m);
+ epv = fminf(epv, gps.epv_m);
+
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);
}
@@ -712,6 +716,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
dt = fmaxf(fminf(0.02, dt), 0.002); // constrain dt from 2 to 20 ms
t_prev = t;
+ /* increase EPH/EPV on each step */
+ eph *= 1.0 + dt;
+ epv += 0.005 * dt; // add 1m to EPV each 200s (baro drift)
+
/* use GPS if it's valid and reference position initialized */
bool use_gps_xy = ref_inited && gps_valid && params.w_xy_gps_p > MIN_VALID_W;
bool use_gps_z = ref_inited && gps_valid && params.w_z_gps_p > MIN_VALID_W;
@@ -723,7 +731,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
xy_src_time = t;
}
- bool can_estimate_xy = (t < xy_src_time + xy_src_timeout);
+ bool can_estimate_xy = eph < max_eph_epv * 1.5;
bool dist_bottom_valid = (t < sonar_valid_time + sonar_valid_timeout);
@@ -784,26 +792,26 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
c += att.R[j][i] * accel_bias_corr[j];
}
- acc_bias[i] += c * params.w_acc_bias * dt;
+ if (isfinite(c)) {
+ acc_bias[i] += c * params.w_acc_bias * dt;
+ }
}
/* inertial filter prediction for altitude */
- inertial_filter_predict(dt, z_est);
+ inertial_filter_predict(dt, z_est, acc[2]);
- if (!(isfinite(z_est[0]) && isfinite(z_est[1]) && isfinite(z_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER Z PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER Z PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(z_est, z_est_prev, sizeof(z_est));
}
/* inertial filter correction for altitude */
inertial_filter_correct(corr_baro, dt, z_est, 0, params.w_z_baro);
inertial_filter_correct(corr_gps[2][0], dt, z_est, 0, w_z_gps_p);
- inertial_filter_correct(corr_acc[2], dt, z_est, 2, params.w_z_acc);
- if (!(isfinite(z_est[0]) && isfinite(z_est[1]) && isfinite(z_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(z_est[0]) && isfinite(z_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER Z CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(z_est, z_est_prev, sizeof(z_est));
- memset(corr_acc, 0, sizeof(corr_acc));
memset(corr_gps, 0, sizeof(corr_gps));
corr_baro = 0;
@@ -813,19 +821,16 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (can_estimate_xy) {
/* inertial filter prediction for position */
- inertial_filter_predict(dt, x_est);
- inertial_filter_predict(dt, y_est);
+ inertial_filter_predict(dt, x_est, acc[0]);
+ inertial_filter_predict(dt, y_est, acc[1]);
- if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(x_est[2]) && isfinite(y_est[0]) && isfinite(y_est[1]) && isfinite(y_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(y_est[0]) && isfinite(y_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER PREDICTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(x_est, x_est_prev, sizeof(x_est));
memcpy(y_est, y_est_prev, sizeof(y_est));
}
/* inertial filter correction for position */
- inertial_filter_correct(corr_acc[0], dt, x_est, 2, params.w_xy_acc);
- inertial_filter_correct(corr_acc[1], dt, y_est, 2, params.w_xy_acc);
-
if (use_flow) {
inertial_filter_correct(corr_flow[0], dt, x_est, 1, params.w_xy_flow * w_flow);
inertial_filter_correct(corr_flow[1], dt, y_est, 1, params.w_xy_flow * w_flow);
@@ -841,11 +846,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(x_est[2]) && isfinite(y_est[0]) && isfinite(y_est[1]) && isfinite(y_est[2]))) {
- write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, corr_acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
+ if (!(isfinite(x_est[0]) && isfinite(x_est[1]) && isfinite(y_est[0]) && isfinite(y_est[1]))) {
+ write_debug_log("BAD ESTIMATE AFTER CORRECTION", dt, x_est, y_est, z_est, x_est_prev, y_est_prev, z_est_prev, acc, corr_gps, w_xy_gps_p, w_xy_gps_v);
memcpy(x_est, x_est_prev, sizeof(x_est));
memcpy(y_est, y_est_prev, sizeof(y_est));
- memset(corr_acc, 0, sizeof(corr_acc));
memset(corr_gps, 0, sizeof(corr_gps));
memset(corr_flow, 0, sizeof(corr_flow));
@@ -922,6 +926,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.landed = landed;
local_pos.yaw = att.yaw;
local_pos.dist_bottom_valid = dist_bottom_valid;
+ local_pos.eph = eph;
+ local_pos.epv = epv;
if (local_pos.dist_bottom_valid) {
local_pos.dist_bottom = -z_est[0] - surface_offset;
@@ -950,9 +956,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.yaw = local_pos.yaw;
- // TODO implement dead-reckoning
- global_pos.eph = gps.eph_m;
- global_pos.epv = gps.epv_m;
+ global_pos.eph = eph;
+ global_pos.epv = epv;
if (vehicle_global_position_pub < 0) {
vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos);
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
index 2e4f26661..8aa08b6f2 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -42,11 +42,9 @@
PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f);
PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f);
-PARAM_DEFINE_FLOAT(INAV_W_Z_ACC, 20.0f);
PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
-PARAM_DEFINE_FLOAT(INAV_W_XY_ACC, 20.0f);
PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f);
PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f);
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f);
@@ -62,11 +60,9 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
{
h->w_z_baro = param_find("INAV_W_Z_BARO");
h->w_z_gps_p = param_find("INAV_W_Z_GPS_P");
- h->w_z_acc = param_find("INAV_W_Z_ACC");
h->w_z_sonar = param_find("INAV_W_Z_SONAR");
h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P");
h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V");
- h->w_xy_acc = param_find("INAV_W_XY_ACC");
h->w_xy_flow = param_find("INAV_W_XY_FLOW");
h->w_gps_flow = param_find("INAV_W_GPS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
@@ -85,11 +81,9 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
{
param_get(h->w_z_baro, &(p->w_z_baro));
param_get(h->w_z_gps_p, &(p->w_z_gps_p));
- param_get(h->w_z_acc, &(p->w_z_acc));
param_get(h->w_z_sonar, &(p->w_z_sonar));
param_get(h->w_xy_gps_p, &(p->w_xy_gps_p));
param_get(h->w_xy_gps_v, &(p->w_xy_gps_v));
- param_get(h->w_xy_acc, &(p->w_xy_acc));
param_get(h->w_xy_flow, &(p->w_xy_flow));
param_get(h->w_gps_flow, &(p->w_gps_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index e2be079d3..08ec996a1 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -43,11 +43,9 @@
struct position_estimator_inav_params {
float w_z_baro;
float w_z_gps_p;
- float w_z_acc;
float w_z_sonar;
float w_xy_gps_p;
float w_xy_gps_v;
- float w_xy_acc;
float w_xy_flow;
float w_gps_flow;
float w_acc_bias;
@@ -63,11 +61,9 @@ struct position_estimator_inav_params {
struct position_estimator_inav_param_handles {
param_t w_z_baro;
param_t w_z_gps_p;
- param_t w_z_acc;
param_t w_z_sonar;
param_t w_xy_gps_p;
param_t w_xy_gps_v;
- param_t w_xy_acc;
param_t w_xy_flow;
param_t w_gps_flow;
param_t w_acc_bias;
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe1.c
deleted file mode 100755
index 977565b8e..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1.c
+++ /dev/null
@@ -1,58 +0,0 @@
-/*
- * kalman_dlqe1.c
- *
- * Code generation for function 'kalman_dlqe1'
- *
- * C source code generated on: Wed Feb 13 20:34:32 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe1.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe1(const real32_T A[9], const real32_T C[3], const real32_T K[3],
- const real32_T x_aposteriori_k[3], real32_T z, real32_T
- x_aposteriori[3])
-{
- printf("[dlqe input]: x_aposteriori_k %12.8f\t %12.8f\t %12.8f\t z:%12.8f\n", (double)(x_aposteriori_k[0]), (double)(x_aposteriori_k[1]), (double)(x_aposteriori_k[2]), (double)z);
- printf("[dlqe input]: C[0]: %12.8f\tC[1] %12.8f\tC[2] %12.8f\n", (double)(C[0]), (double)(C[1]), (double)(C[2]));
- real32_T y;
- int32_T i0;
- real32_T b_y[3];
- int32_T i1;
- real32_T f0;
- y = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- b_y[i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- b_y[i0] += C[i1] * A[i1 + 3 * i0];
- }
-
- y += b_y[i0] * x_aposteriori_k[i0];
- }
-
- y = z - y;
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
- }
-
- x_aposteriori[i0] = f0 + K[i0] * y;
- }
- //printf("[dlqe output]: x_aposteriori %12.8f\t %12.8f\t %12.8f\n", (double)(x_aposteriori[0]), (double)(x_aposteriori[1]), (double)(x_aposteriori[2]));
-}
-
-/* End of code generation (kalman_dlqe1.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe1.h
deleted file mode 100755
index 2f5330563..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * kalman_dlqe1.h
- *
- * Code generation for function 'kalman_dlqe1'
- *
- * C source code generated on: Wed Feb 13 20:34:32 2013
- *
- */
-
-#ifndef __KALMAN_DLQE1_H__
-#define __KALMAN_DLQE1_H__
-/* Include files */
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "kalman_dlqe1_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe1(const real32_T A[9], const real32_T C[3], const real32_T K[3], const real32_T x_aposteriori_k[3], real32_T z, real32_T x_aposteriori[3]);
-#endif
-/* End of code generation (kalman_dlqe1.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.c
deleted file mode 100755
index 6627f76e9..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * kalman_dlqe1_initialize.c
- *
- * Code generation for function 'kalman_dlqe1_initialize'
- *
- * C source code generated on: Wed Feb 13 20:34:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe1.h"
-#include "kalman_dlqe1_initialize.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe1_initialize(void)
-{
- rt_InitInfAndNaN(8U);
-}
-
-/* End of code generation (kalman_dlqe1_initialize.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.h
deleted file mode 100755
index a77eb5712..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_initialize.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * kalman_dlqe1_initialize.h
- *
- * Code generation for function 'kalman_dlqe1_initialize'
- *
- * C source code generated on: Wed Feb 13 20:34:31 2013
- *
- */
-
-#ifndef __KALMAN_DLQE1_INITIALIZE_H__
-#define __KALMAN_DLQE1_INITIALIZE_H__
-/* Include files */
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "kalman_dlqe1_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe1_initialize(void);
-#endif
-/* End of code generation (kalman_dlqe1_initialize.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.c
deleted file mode 100755
index a65536f79..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * kalman_dlqe1_terminate.c
- *
- * Code generation for function 'kalman_dlqe1_terminate'
- *
- * C source code generated on: Wed Feb 13 20:34:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe1.h"
-#include "kalman_dlqe1_terminate.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe1_terminate(void)
-{
- /* (no terminate code required) */
-}
-
-/* End of code generation (kalman_dlqe1_terminate.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.h
deleted file mode 100755
index 100c7f76c..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_terminate.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/*
- * kalman_dlqe1_terminate.h
- *
- * Code generation for function 'kalman_dlqe1_terminate'
- *
- * C source code generated on: Wed Feb 13 20:34:32 2013
- *
- */
-
-#ifndef __KALMAN_DLQE1_TERMINATE_H__
-#define __KALMAN_DLQE1_TERMINATE_H__
-/* Include files */
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "kalman_dlqe1_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe1_terminate(void);
-#endif
-/* End of code generation (kalman_dlqe1_terminate.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_types.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe1_types.h
deleted file mode 100755
index d4b2c2d61..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe1_types.h
+++ /dev/null
@@ -1,16 +0,0 @@
-/*
- * kalman_dlqe1_types.h
- *
- * Code generation for function 'kalman_dlqe1'
- *
- * C source code generated on: Wed Feb 13 20:34:31 2013
- *
- */
-
-#ifndef __KALMAN_DLQE1_TYPES_H__
-#define __KALMAN_DLQE1_TYPES_H__
-
-/* Type Definitions */
-
-#endif
-/* End of code generation (kalman_dlqe1_types.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe2.c
deleted file mode 100755
index 11b999064..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2.c
+++ /dev/null
@@ -1,119 +0,0 @@
-/*
- * kalman_dlqe2.c
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe2.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-static real32_T rt_powf_snf(real32_T u0, real32_T u1);
-
-/* Function Definitions */
-static real32_T rt_powf_snf(real32_T u0, real32_T u1)
-{
- real32_T y;
- real32_T f1;
- real32_T f2;
- if (rtIsNaNF(u0) || rtIsNaNF(u1)) {
- y = ((real32_T)rtNaN);
- } else {
- f1 = (real32_T)fabs(u0);
- f2 = (real32_T)fabs(u1);
- if (rtIsInfF(u1)) {
- if (f1 == 1.0F) {
- y = ((real32_T)rtNaN);
- } else if (f1 > 1.0F) {
- if (u1 > 0.0F) {
- y = ((real32_T)rtInf);
- } else {
- y = 0.0F;
- }
- } else if (u1 > 0.0F) {
- y = 0.0F;
- } else {
- y = ((real32_T)rtInf);
- }
- } else if (f2 == 0.0F) {
- y = 1.0F;
- } else if (f2 == 1.0F) {
- if (u1 > 0.0F) {
- y = u0;
- } else {
- y = 1.0F / u0;
- }
- } else if (u1 == 2.0F) {
- y = u0 * u0;
- } else if ((u1 == 0.5F) && (u0 >= 0.0F)) {
- y = (real32_T)sqrt(u0);
- } else if ((u0 < 0.0F) && (u1 > (real32_T)floor(u1))) {
- y = ((real32_T)rtNaN);
- } else {
- y = (real32_T)pow(u0, u1);
- }
- }
-
- return y;
-}
-
-void kalman_dlqe2(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const
- real32_T x_aposteriori_k[3], real32_T z, real32_T
- x_aposteriori[3])
-{
- //printf("[dqle2] dt: %12.8f\tvk1 %12.8f\tk2: %12.8f\tk3: %12.8f\n", (double)(dt), (double)(k1), (double)(k2), (double)(k3));
- //printf("[dqle2] dt: %8.4f\n", (double)(dt));//, (double)(k1), (double)(k2), (double)(k3));
- real32_T A[9];
- real32_T y;
- int32_T i0;
- static const int8_T iv0[3] = { 0, 0, 1 };
-
- real32_T b_k1[3];
- int32_T i1;
- static const int8_T iv1[3] = { 1, 0, 0 };
-
- real32_T f0;
- A[0] = 1.0F;
- A[3] = dt;
- A[6] = 0.5F * rt_powf_snf(dt, 2.0F);
- A[1] = 0.0F;
- A[4] = 1.0F;
- A[7] = dt;
- y = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- A[2 + 3 * i0] = (real32_T)iv0[i0];
- b_k1[i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- b_k1[i0] += (real32_T)iv1[i1] * A[i1 + 3 * i0];
- }
-
- y += b_k1[i0] * x_aposteriori_k[i0];
- }
-
- y = z - y;
- b_k1[0] = k1;
- b_k1[1] = k2;
- b_k1[2] = k3;
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
- }
-
- x_aposteriori[i0] = f0 + b_k1[i0] * y;
- }
-}
-
-/* End of code generation (kalman_dlqe2.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe2.h
deleted file mode 100755
index 30170ae22..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2.h
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * kalman_dlqe2.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-#ifndef __KALMAN_DLQE2_H__
-#define __KALMAN_DLQE2_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe2_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe2(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const real32_T x_aposteriori_k[3], real32_T z, real32_T x_aposteriori[3]);
-#endif
-/* End of code generation (kalman_dlqe2.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.c
deleted file mode 100755
index de5a1d8aa..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * kalman_dlqe2_initialize.c
- *
- * Code generation for function 'kalman_dlqe2_initialize'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe2.h"
-#include "kalman_dlqe2_initialize.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe2_initialize(void)
-{
- rt_InitInfAndNaN(8U);
-}
-
-/* End of code generation (kalman_dlqe2_initialize.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.h
deleted file mode 100755
index 3d507ff31..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_initialize.h
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * kalman_dlqe2_initialize.h
- *
- * Code generation for function 'kalman_dlqe2_initialize'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-#ifndef __KALMAN_DLQE2_INITIALIZE_H__
-#define __KALMAN_DLQE2_INITIALIZE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe2_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe2_initialize(void);
-#endif
-/* End of code generation (kalman_dlqe2_initialize.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.c
deleted file mode 100755
index 0757c878c..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * kalman_dlqe2_terminate.c
- *
- * Code generation for function 'kalman_dlqe2_terminate'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe2.h"
-#include "kalman_dlqe2_terminate.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe2_terminate(void)
-{
- /* (no terminate code required) */
-}
-
-/* End of code generation (kalman_dlqe2_terminate.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.h
deleted file mode 100755
index 23995020b..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_terminate.h
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * kalman_dlqe2_terminate.h
- *
- * Code generation for function 'kalman_dlqe2_terminate'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-#ifndef __KALMAN_DLQE2_TERMINATE_H__
-#define __KALMAN_DLQE2_TERMINATE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe2_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe2_terminate(void);
-#endif
-/* End of code generation (kalman_dlqe2_terminate.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_types.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe2_types.h
deleted file mode 100755
index f7a04d908..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe2_types.h
+++ /dev/null
@@ -1,16 +0,0 @@
-/*
- * kalman_dlqe2_types.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:28 2013
- *
- */
-
-#ifndef __KALMAN_DLQE2_TYPES_H__
-#define __KALMAN_DLQE2_TYPES_H__
-
-/* Type Definitions */
-
-#endif
-/* End of code generation (kalman_dlqe2_types.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe3.c
deleted file mode 100755
index 9efe2ea7a..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3.c
+++ /dev/null
@@ -1,137 +0,0 @@
-/*
- * kalman_dlqe3.c
- *
- * Code generation for function 'kalman_dlqe3'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe3.h"
-#include "randn.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-static real32_T rt_powf_snf(real32_T u0, real32_T u1);
-
-/* Function Definitions */
-static real32_T rt_powf_snf(real32_T u0, real32_T u1)
-{
- real32_T y;
- real32_T f1;
- real32_T f2;
- if (rtIsNaNF(u0) || rtIsNaNF(u1)) {
- y = ((real32_T)rtNaN);
- } else {
- f1 = (real32_T)fabs(u0);
- f2 = (real32_T)fabs(u1);
- if (rtIsInfF(u1)) {
- if (f1 == 1.0F) {
- y = ((real32_T)rtNaN);
- } else if (f1 > 1.0F) {
- if (u1 > 0.0F) {
- y = ((real32_T)rtInf);
- } else {
- y = 0.0F;
- }
- } else if (u1 > 0.0F) {
- y = 0.0F;
- } else {
- y = ((real32_T)rtInf);
- }
- } else if (f2 == 0.0F) {
- y = 1.0F;
- } else if (f2 == 1.0F) {
- if (u1 > 0.0F) {
- y = u0;
- } else {
- y = 1.0F / u0;
- }
- } else if (u1 == 2.0F) {
- y = u0 * u0;
- } else if ((u1 == 0.5F) && (u0 >= 0.0F)) {
- y = (real32_T)sqrt(u0);
- } else if ((u0 < 0.0F) && (u1 > (real32_T)floor(u1))) {
- y = ((real32_T)rtNaN);
- } else {
- y = (real32_T)pow(u0, u1);
- }
- }
-
- return y;
-}
-
-void kalman_dlqe3(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const
- real32_T x_aposteriori_k[3], real32_T z, real32_T posUpdate,
- real32_T addNoise, real32_T sigma, real32_T x_aposteriori[3])
-{
- real32_T A[9];
- int32_T i0;
- static const int8_T iv0[3] = { 0, 0, 1 };
-
- real_T b;
- real32_T y;
- real32_T b_y[3];
- int32_T i1;
- static const int8_T iv1[3] = { 1, 0, 0 };
-
- real32_T b_k1[3];
- real32_T f0;
- A[0] = 1.0F;
- A[3] = dt;
- A[6] = 0.5F * rt_powf_snf(dt, 2.0F);
- A[1] = 0.0F;
- A[4] = 1.0F;
- A[7] = dt;
- for (i0 = 0; i0 < 3; i0++) {
- A[2 + 3 * i0] = (real32_T)iv0[i0];
- }
-
- if (addNoise == 1.0F) {
- b = randn();
- z += sigma * (real32_T)b;
- }
-
- if (posUpdate != 0.0F) {
- y = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- b_y[i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- b_y[i0] += (real32_T)iv1[i1] * A[i1 + 3 * i0];
- }
-
- y += b_y[i0] * x_aposteriori_k[i0];
- }
-
- y = z - y;
- b_k1[0] = k1;
- b_k1[1] = k2;
- b_k1[2] = k3;
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
- }
-
- x_aposteriori[i0] = f0 + b_k1[i0] * y;
- }
- } else {
- for (i0 = 0; i0 < 3; i0++) {
- x_aposteriori[i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- x_aposteriori[i0] += A[i0 + 3 * i1] * x_aposteriori_k[i1];
- }
- }
- }
-}
-
-/* End of code generation (kalman_dlqe3.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe3.h
deleted file mode 100755
index 9bbffbbb3..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3.h
+++ /dev/null
@@ -1,33 +0,0 @@
-/*
- * kalman_dlqe3.h
- *
- * Code generation for function 'kalman_dlqe3'
- *
- * C source code generated on: Tue Feb 19 15:26:32 2013
- *
- */
-
-#ifndef __KALMAN_DLQE3_H__
-#define __KALMAN_DLQE3_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include <string.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe3_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe3(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const real32_T x_aposteriori_k[3], real32_T z, real32_T posUpdate, real32_T addNoise, real32_T sigma, real32_T x_aposteriori[3]);
-#endif
-/* End of code generation (kalman_dlqe3.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.c
deleted file mode 100755
index 8f2275c13..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.c
+++ /dev/null
@@ -1,32 +0,0 @@
-/*
- * kalman_dlqe3_data.c
- *
- * Code generation for function 'kalman_dlqe3_data'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe3.h"
-#include "kalman_dlqe3_data.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-uint32_T method;
-uint32_T state[2];
-uint32_T b_method;
-uint32_T b_state;
-uint32_T c_state[2];
-boolean_T state_not_empty;
-
-/* Function Declarations */
-
-/* Function Definitions */
-/* End of code generation (kalman_dlqe3_data.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.h
deleted file mode 100755
index 952eb7b89..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_data.h
+++ /dev/null
@@ -1,38 +0,0 @@
-/*
- * kalman_dlqe3_data.h
- *
- * Code generation for function 'kalman_dlqe3_data'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-#ifndef __KALMAN_DLQE3_DATA_H__
-#define __KALMAN_DLQE3_DATA_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include <string.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe3_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-extern uint32_T method;
-extern uint32_T state[2];
-extern uint32_T b_method;
-extern uint32_T b_state;
-extern uint32_T c_state[2];
-extern boolean_T state_not_empty;
-
-/* Variable Definitions */
-
-/* Function Declarations */
-#endif
-/* End of code generation (kalman_dlqe3_data.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.c
deleted file mode 100755
index b87d604c4..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.c
+++ /dev/null
@@ -1,47 +0,0 @@
-/*
- * kalman_dlqe3_initialize.c
- *
- * Code generation for function 'kalman_dlqe3_initialize'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe3.h"
-#include "kalman_dlqe3_initialize.h"
-#include "kalman_dlqe3_data.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe3_initialize(void)
-{
- int32_T i;
- static const uint32_T uv0[2] = { 362436069U, 0U };
-
- rt_InitInfAndNaN(8U);
- state_not_empty = FALSE;
- b_state = 1144108930U;
- b_method = 7U;
- method = 0U;
- for (i = 0; i < 2; i++) {
- c_state[i] = 362436069U + 158852560U * (uint32_T)i;
- state[i] = uv0[i];
- }
-
- if (state[1] == 0U) {
- state[1] = 521288629U;
- }
-}
-
-/* End of code generation (kalman_dlqe3_initialize.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.h
deleted file mode 100755
index 9dee90f9e..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_initialize.h
+++ /dev/null
@@ -1,33 +0,0 @@
-/*
- * kalman_dlqe3_initialize.h
- *
- * Code generation for function 'kalman_dlqe3_initialize'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-#ifndef __KALMAN_DLQE3_INITIALIZE_H__
-#define __KALMAN_DLQE3_INITIALIZE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include <string.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe3_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe3_initialize(void);
-#endif
-/* End of code generation (kalman_dlqe3_initialize.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.c b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.c
deleted file mode 100755
index b00858205..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * kalman_dlqe3_terminate.c
- *
- * Code generation for function 'kalman_dlqe3_terminate'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe3.h"
-#include "kalman_dlqe3_terminate.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void kalman_dlqe3_terminate(void)
-{
- /* (no terminate code required) */
-}
-
-/* End of code generation (kalman_dlqe3_terminate.c) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.h
deleted file mode 100755
index 69cc85c76..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_terminate.h
+++ /dev/null
@@ -1,33 +0,0 @@
-/*
- * kalman_dlqe3_terminate.h
- *
- * Code generation for function 'kalman_dlqe3_terminate'
- *
- * C source code generated on: Tue Feb 19 15:26:31 2013
- *
- */
-
-#ifndef __KALMAN_DLQE3_TERMINATE_H__
-#define __KALMAN_DLQE3_TERMINATE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include <string.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe3_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void kalman_dlqe3_terminate(void);
-#endif
-/* End of code generation (kalman_dlqe3_terminate.h) */
diff --git a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_types.h b/src/modules/position_estimator_mc/codegen/kalman_dlqe3_types.h
deleted file mode 100755
index f36ea4557..000000000
--- a/src/modules/position_estimator_mc/codegen/kalman_dlqe3_types.h
+++ /dev/null
@@ -1,16 +0,0 @@
-/*
- * kalman_dlqe3_types.h
- *
- * Code generation for function 'kalman_dlqe3'
- *
- * C source code generated on: Tue Feb 19 15:26:30 2013
- *
- */
-
-#ifndef __KALMAN_DLQE3_TYPES_H__
-#define __KALMAN_DLQE3_TYPES_H__
-
-/* Type Definitions */
-
-#endif
-/* End of code generation (kalman_dlqe3_types.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.c
deleted file mode 100755
index 5139848bc..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.c
+++ /dev/null
@@ -1,136 +0,0 @@
-/*
- * positionKalmanFilter1D.c
- *
- * Code generation for function 'positionKalmanFilter1D'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D(const real32_T A[9], const real32_T B[3], const
- real32_T C[3], const real32_T x_aposteriori_k[3], const real32_T
- P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T
- Q[9], real32_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3],
- real32_T P_aposteriori[9])
-{
- int32_T i0;
- real32_T f0;
- int32_T k;
- real32_T b_A[9];
- int32_T i1;
- real32_T P_apriori[9];
- real32_T y;
- real32_T K[3];
- real32_T S;
- int8_T I[9];
-
- /* prediction */
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (k = 0; k < 3; k++) {
- f0 += A[i0 + 3 * k] * x_aposteriori_k[k];
- }
-
- x_aposteriori[i0] = f0 + B[i0] * u;
- }
-
- for (i0 = 0; i0 < 3; i0++) {
- for (k = 0; k < 3; k++) {
- b_A[i0 + 3 * k] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- b_A[i0 + 3 * k] += A[i0 + 3 * i1] * P_aposteriori_k[i1 + 3 * k];
- }
- }
- }
-
- for (i0 = 0; i0 < 3; i0++) {
- for (k = 0; k < 3; k++) {
- f0 = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- f0 += b_A[i0 + 3 * i1] * A[k + 3 * i1];
- }
-
- P_apriori[i0 + 3 * k] = f0 + Q[i0 + 3 * k];
- }
- }
-
- if ((real32_T)fabs(u) < thresh) {
- x_aposteriori[1] *= decay;
- }
-
- /* update */
- if (gps_update == 1) {
- y = 0.0F;
- for (k = 0; k < 3; k++) {
- y += C[k] * x_aposteriori[k];
- K[k] = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- K[k] += C[i0] * P_apriori[i0 + 3 * k];
- }
- }
-
- y = z - y;
- S = 0.0F;
- for (k = 0; k < 3; k++) {
- S += K[k] * C[k];
- }
-
- S += R;
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (k = 0; k < 3; k++) {
- f0 += P_apriori[i0 + 3 * k] * C[k];
- }
-
- K[i0] = f0 / S;
- }
-
- for (i0 = 0; i0 < 3; i0++) {
- x_aposteriori[i0] += K[i0] * y;
- }
-
- for (i0 = 0; i0 < 9; i0++) {
- I[i0] = 0;
- }
-
- for (k = 0; k < 3; k++) {
- I[k + 3 * k] = 1;
- }
-
- for (i0 = 0; i0 < 3; i0++) {
- for (k = 0; k < 3; k++) {
- b_A[k + 3 * i0] = (real32_T)I[k + 3 * i0] - K[k] * C[i0];
- }
- }
-
- for (i0 = 0; i0 < 3; i0++) {
- for (k = 0; k < 3; k++) {
- P_aposteriori[i0 + 3 * k] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- P_aposteriori[i0 + 3 * k] += b_A[i0 + 3 * i1] * P_apriori[i1 + 3 * k];
- }
- }
- }
- } else {
- for (i0 = 0; i0 < 9; i0++) {
- P_aposteriori[i0] = P_apriori[i0];
- }
- }
-}
-
-/* End of code generation (positionKalmanFilter1D.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.h
deleted file mode 100755
index 205c8eb4e..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D.h
- *
- * Code generation for function 'positionKalmanFilter1D'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_H__
-#define __POSITIONKALMANFILTER1D_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D(const real32_T A[9], const real32_T B[3], const real32_T C[3], const real32_T x_aposteriori_k[3], const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T Q[9], real32_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3], real32_T P_aposteriori[9]);
-#endif
-/* End of code generation (positionKalmanFilter1D.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.c
deleted file mode 100755
index 4c535618a..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.c
+++ /dev/null
@@ -1,157 +0,0 @@
-/*
- * positionKalmanFilter1D_dT.c
- *
- * Code generation for function 'positionKalmanFilter1D_dT'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D_dT.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D_dT(real32_T dT, const real32_T x_aposteriori_k[3],
- const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update,
- const real32_T Q[9], real_T R, real32_T thresh, real32_T decay, real32_T
- x_aposteriori[3], real32_T P_aposteriori[9])
-{
- real32_T A[9];
- int32_T i;
- static const int8_T iv0[3] = { 0, 0, 1 };
-
- real32_T K[3];
- real32_T f0;
- int32_T i0;
- real32_T b_A[9];
- int32_T i1;
- real32_T P_apriori[9];
- static const int8_T iv1[3] = { 1, 0, 0 };
-
- real32_T fv0[3];
- real32_T y;
- static const int8_T iv2[3] = { 1, 0, 0 };
-
- real32_T S;
- int8_T I[9];
-
- /* dynamics */
- A[0] = 1.0F;
- A[3] = dT;
- A[6] = -0.5F * dT * dT;
- A[1] = 0.0F;
- A[4] = 1.0F;
- A[7] = -dT;
- for (i = 0; i < 3; i++) {
- A[2 + 3 * i] = (real32_T)iv0[i];
- }
-
- /* prediction */
- K[0] = 0.5F * dT * dT;
- K[1] = dT;
- K[2] = 0.0F;
- for (i = 0; i < 3; i++) {
- f0 = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- f0 += A[i + 3 * i0] * x_aposteriori_k[i0];
- }
-
- x_aposteriori[i] = f0 + K[i] * u;
- }
-
- for (i = 0; i < 3; i++) {
- for (i0 = 0; i0 < 3; i0++) {
- b_A[i + 3 * i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- b_A[i + 3 * i0] += A[i + 3 * i1] * P_aposteriori_k[i1 + 3 * i0];
- }
- }
- }
-
- for (i = 0; i < 3; i++) {
- for (i0 = 0; i0 < 3; i0++) {
- f0 = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- f0 += b_A[i + 3 * i1] * A[i0 + 3 * i1];
- }
-
- P_apriori[i + 3 * i0] = f0 + Q[i + 3 * i0];
- }
- }
-
- if ((real32_T)fabs(u) < thresh) {
- x_aposteriori[1] *= decay;
- }
-
- /* update */
- if (gps_update == 1) {
- f0 = 0.0F;
- for (i = 0; i < 3; i++) {
- f0 += (real32_T)iv1[i] * x_aposteriori[i];
- fv0[i] = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- fv0[i] += (real32_T)iv1[i0] * P_apriori[i0 + 3 * i];
- }
- }
-
- y = z - f0;
- f0 = 0.0F;
- for (i = 0; i < 3; i++) {
- f0 += fv0[i] * (real32_T)iv2[i];
- }
-
- S = f0 + (real32_T)R;
- for (i = 0; i < 3; i++) {
- f0 = 0.0F;
- for (i0 = 0; i0 < 3; i0++) {
- f0 += P_apriori[i + 3 * i0] * (real32_T)iv2[i0];
- }
-
- K[i] = f0 / S;
- }
-
- for (i = 0; i < 3; i++) {
- x_aposteriori[i] += K[i] * y;
- }
-
- for (i = 0; i < 9; i++) {
- I[i] = 0;
- }
-
- for (i = 0; i < 3; i++) {
- I[i + 3 * i] = 1;
- }
-
- for (i = 0; i < 3; i++) {
- for (i0 = 0; i0 < 3; i0++) {
- A[i0 + 3 * i] = (real32_T)I[i0 + 3 * i] - K[i0] * (real32_T)iv1[i];
- }
- }
-
- for (i = 0; i < 3; i++) {
- for (i0 = 0; i0 < 3; i0++) {
- P_aposteriori[i + 3 * i0] = 0.0F;
- for (i1 = 0; i1 < 3; i1++) {
- P_aposteriori[i + 3 * i0] += A[i + 3 * i1] * P_apriori[i1 + 3 * i0];
- }
- }
- }
- } else {
- for (i = 0; i < 9; i++) {
- P_aposteriori[i] = P_apriori[i];
- }
- }
-}
-
-/* End of code generation (positionKalmanFilter1D_dT.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.h
deleted file mode 100755
index 94cbe2ce6..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_dT.h
- *
- * Code generation for function 'positionKalmanFilter1D_dT'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_DT_H__
-#define __POSITIONKALMANFILTER1D_DT_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_dT_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D_dT(real32_T dT, const real32_T x_aposteriori_k[3], const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T Q[9], real_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3], real32_T P_aposteriori[9]);
-#endif
-/* End of code generation (positionKalmanFilter1D_dT.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.c
deleted file mode 100755
index aa89f8a9d..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_dT_initialize.c
- *
- * Code generation for function 'positionKalmanFilter1D_dT_initialize'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D_dT.h"
-#include "positionKalmanFilter1D_dT_initialize.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D_dT_initialize(void)
-{
- rt_InitInfAndNaN(8U);
-}
-
-/* End of code generation (positionKalmanFilter1D_dT_initialize.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.h
deleted file mode 100755
index 8d358a9a3..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_initialize.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_dT_initialize.h
- *
- * Code generation for function 'positionKalmanFilter1D_dT_initialize'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_DT_INITIALIZE_H__
-#define __POSITIONKALMANFILTER1D_DT_INITIALIZE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_dT_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D_dT_initialize(void);
-#endif
-/* End of code generation (positionKalmanFilter1D_dT_initialize.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.c
deleted file mode 100755
index 20ed2edbb..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_dT_terminate.c
- *
- * Code generation for function 'positionKalmanFilter1D_dT_terminate'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D_dT.h"
-#include "positionKalmanFilter1D_dT_terminate.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D_dT_terminate(void)
-{
- /* (no terminate code required) */
-}
-
-/* End of code generation (positionKalmanFilter1D_dT_terminate.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.h
deleted file mode 100755
index 5eb5807a0..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_terminate.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_dT_terminate.h
- *
- * Code generation for function 'positionKalmanFilter1D_dT_terminate'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_DT_TERMINATE_H__
-#define __POSITIONKALMANFILTER1D_DT_TERMINATE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_dT_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D_dT_terminate(void);
-#endif
-/* End of code generation (positionKalmanFilter1D_dT_terminate.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_types.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_types.h
deleted file mode 100755
index 43e5f016c..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_dT_types.h
+++ /dev/null
@@ -1,16 +0,0 @@
-/*
- * positionKalmanFilter1D_dT_types.h
- *
- * Code generation for function 'positionKalmanFilter1D_dT'
- *
- * C source code generated on: Fri Nov 30 17:37:33 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_DT_TYPES_H__
-#define __POSITIONKALMANFILTER1D_DT_TYPES_H__
-
-/* Type Definitions */
-
-#endif
-/* End of code generation (positionKalmanFilter1D_dT_types.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.c
deleted file mode 100755
index 5bd87c390..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_initialize.c
- *
- * Code generation for function 'positionKalmanFilter1D_initialize'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D.h"
-#include "positionKalmanFilter1D_initialize.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D_initialize(void)
-{
- rt_InitInfAndNaN(8U);
-}
-
-/* End of code generation (positionKalmanFilter1D_initialize.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.h
deleted file mode 100755
index 44bce472f..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_initialize.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_initialize.h
- *
- * Code generation for function 'positionKalmanFilter1D_initialize'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_INITIALIZE_H__
-#define __POSITIONKALMANFILTER1D_INITIALIZE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D_initialize(void);
-#endif
-/* End of code generation (positionKalmanFilter1D_initialize.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.c b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.c
deleted file mode 100755
index 41e11936f..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.c
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_terminate.c
- *
- * Code generation for function 'positionKalmanFilter1D_terminate'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "positionKalmanFilter1D.h"
-#include "positionKalmanFilter1D_terminate.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-
-/* Function Definitions */
-void positionKalmanFilter1D_terminate(void)
-{
- /* (no terminate code required) */
-}
-
-/* End of code generation (positionKalmanFilter1D_terminate.c) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.h
deleted file mode 100755
index e84ea01bc..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_terminate.h
+++ /dev/null
@@ -1,31 +0,0 @@
-/*
- * positionKalmanFilter1D_terminate.h
- *
- * Code generation for function 'positionKalmanFilter1D_terminate'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_TERMINATE_H__
-#define __POSITIONKALMANFILTER1D_TERMINATE_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-
-#include "rtwtypes.h"
-#include "positionKalmanFilter1D_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern void positionKalmanFilter1D_terminate(void);
-#endif
-/* End of code generation (positionKalmanFilter1D_terminate.h) */
diff --git a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_types.h b/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_types.h
deleted file mode 100755
index 4b473f56f..000000000
--- a/src/modules/position_estimator_mc/codegen/positionKalmanFilter1D_types.h
+++ /dev/null
@@ -1,16 +0,0 @@
-/*
- * positionKalmanFilter1D_types.h
- *
- * Code generation for function 'positionKalmanFilter1D'
- *
- * C source code generated on: Fri Nov 30 14:26:11 2012
- *
- */
-
-#ifndef __POSITIONKALMANFILTER1D_TYPES_H__
-#define __POSITIONKALMANFILTER1D_TYPES_H__
-
-/* Type Definitions */
-
-#endif
-/* End of code generation (positionKalmanFilter1D_types.h) */
diff --git a/src/modules/position_estimator_mc/codegen/randn.c b/src/modules/position_estimator_mc/codegen/randn.c
deleted file mode 100755
index 51aef7b76..000000000
--- a/src/modules/position_estimator_mc/codegen/randn.c
+++ /dev/null
@@ -1,524 +0,0 @@
-/*
- * randn.c
- *
- * Code generation for function 'randn'
- *
- * C source code generated on: Tue Feb 19 15:26:32 2013
- *
- */
-
-/* Include files */
-#include "rt_nonfinite.h"
-#include "kalman_dlqe3.h"
-#include "randn.h"
-#include "kalman_dlqe3_data.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-static uint32_T d_state[625];
-
-/* Function Declarations */
-static real_T b_genrandu(uint32_T mt[625]);
-static real_T eml_rand_mt19937ar(uint32_T e_state[625]);
-static real_T eml_rand_shr3cong(uint32_T e_state[2]);
-static void genrand_uint32_vector(uint32_T mt[625], uint32_T u[2]);
-static void genrandu(uint32_T s, uint32_T *e_state, real_T *r);
-static void twister_state_vector(uint32_T mt[625], real_T seed);
-
-/* Function Definitions */
-static real_T b_genrandu(uint32_T mt[625])
-{
- real_T r;
- int32_T exitg1;
- uint32_T u[2];
- boolean_T isvalid;
- int32_T k;
- boolean_T exitg2;
-
- /* <LEGAL> This is a uniform (0,1) pseudorandom number generator based on: */
- /* <LEGAL> */
- /* <LEGAL> A C-program for MT19937, with initialization improved 2002/1/26. */
- /* <LEGAL> Coded by Takuji Nishimura and Makoto Matsumoto. */
- /* <LEGAL> */
- /* <LEGAL> Copyright (C) 1997 - 2002, Makoto Matsumoto and Takuji Nishimura, */
- /* <LEGAL> All rights reserved. */
- /* <LEGAL> */
- /* <LEGAL> Redistribution and use in source and binary forms, with or without */
- /* <LEGAL> modification, are permitted provided that the following conditions */
- /* <LEGAL> are met: */
- /* <LEGAL> */
- /* <LEGAL> 1. Redistributions of source code must retain the above copyright */
- /* <LEGAL> notice, this list of conditions and the following disclaimer. */
- /* <LEGAL> */
- /* <LEGAL> 2. Redistributions in binary form must reproduce the above copyright */
- /* <LEGAL> notice, this list of conditions and the following disclaimer in the */
- /* <LEGAL> documentation and/or other materials provided with the distribution. */
- /* <LEGAL> */
- /* <LEGAL> 3. The names of its contributors may not be used to endorse or promote */
- /* <LEGAL> products derived from this software without specific prior written */
- /* <LEGAL> permission. */
- /* <LEGAL> */
- /* <LEGAL> THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS */
- /* <LEGAL> "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT */
- /* <LEGAL> LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR */
- /* <LEGAL> A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR */
- /* <LEGAL> CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, */
- /* <LEGAL> EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, */
- /* <LEGAL> PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR */
- /* <LEGAL> PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF */
- /* <LEGAL> LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING */
- /* <LEGAL> NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS */
- /* <LEGAL> SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. */
- do {
- exitg1 = 0;
- genrand_uint32_vector(mt, u);
- r = 1.1102230246251565E-16 * ((real_T)(u[0] >> 5U) * 6.7108864E+7 + (real_T)
- (u[1] >> 6U));
- if (r == 0.0) {
- if ((mt[624] >= 1U) && (mt[624] < 625U)) {
- isvalid = TRUE;
- } else {
- isvalid = FALSE;
- }
-
- if (isvalid) {
- isvalid = FALSE;
- k = 1;
- exitg2 = FALSE;
- while ((exitg2 == FALSE) && (k < 625)) {
- if (mt[k - 1] == 0U) {
- k++;
- } else {
- isvalid = TRUE;
- exitg2 = TRUE;
- }
- }
- }
-
- if (!isvalid) {
- twister_state_vector(mt, 5489.0);
- }
- } else {
- exitg1 = 1;
- }
- } while (exitg1 == 0);
-
- return r;
-}
-
-static real_T eml_rand_mt19937ar(uint32_T e_state[625])
-{
- real_T r;
- int32_T exitg1;
- uint32_T u32[2];
- int32_T i;
- static const real_T dv1[257] = { 0.0, 0.215241895984875, 0.286174591792068,
- 0.335737519214422, 0.375121332878378, 0.408389134611989, 0.43751840220787,
- 0.46363433679088, 0.487443966139235, 0.50942332960209, 0.529909720661557,
- 0.549151702327164, 0.567338257053817, 0.584616766106378, 0.601104617755991,
- 0.61689699000775, 0.63207223638606, 0.646695714894993, 0.660822574244419,
- 0.674499822837293, 0.687767892795788, 0.700661841106814, 0.713212285190975,
- 0.725446140909999, 0.737387211434295, 0.749056662017815, 0.760473406430107,
- 0.771654424224568, 0.782615023307232, 0.793369058840623, 0.80392911698997,
- 0.814306670135215, 0.824512208752291, 0.834555354086381, 0.844444954909153,
- 0.854189171008163, 0.863795545553308, 0.87327106808886, 0.882622229585165,
- 0.891855070732941, 0.900975224461221, 0.909987953496718, 0.91889818364959,
- 0.927710533401999, 0.936429340286575, 0.945058684468165, 0.953602409881086,
- 0.96206414322304, 0.970447311064224, 0.978755155294224, 0.986990747099062,
- 0.99515699963509, 1.00325667954467, 1.01129241744, 1.01926671746548,
- 1.02718196603564, 1.03504043983344, 1.04284431314415, 1.05059566459093,
- 1.05829648333067, 1.06594867476212, 1.07355406579244, 1.0811144097034,
- 1.08863139065398, 1.09610662785202, 1.10354167942464, 1.11093804601357,
- 1.11829717411934, 1.12562045921553, 1.13290924865253, 1.14016484436815,
- 1.14738850542085, 1.15458145035993, 1.16174485944561, 1.16887987673083,
- 1.17598761201545, 1.18306914268269, 1.19012551542669, 1.19715774787944,
- 1.20416683014438, 1.2111537262437, 1.21811937548548, 1.22506469375653,
- 1.23199057474614, 1.23889789110569, 1.24578749554863, 1.2526602218949,
- 1.25951688606371, 1.26635828701823, 1.27318520766536, 1.27999841571382,
- 1.28679866449324, 1.29358669373695, 1.30036323033084, 1.30712898903073,
- 1.31388467315022, 1.32063097522106, 1.32736857762793, 1.33409815321936,
- 1.3408203658964, 1.34753587118059, 1.35424531676263, 1.36094934303328,
- 1.36764858359748, 1.37434366577317, 1.38103521107586, 1.38772383568998,
- 1.39441015092814, 1.40109476367925, 1.4077782768464, 1.41446128977547,
- 1.42114439867531, 1.42782819703026, 1.43451327600589, 1.44120022484872,
- 1.44788963128058, 1.45458208188841, 1.46127816251028, 1.46797845861808,
- 1.47468355569786, 1.48139403962819, 1.48811049705745, 1.49483351578049,
- 1.50156368511546, 1.50830159628131, 1.51504784277671, 1.521803020761,
- 1.52856772943771, 1.53534257144151, 1.542128153229, 1.54892508547417,
- 1.55573398346918, 1.56255546753104, 1.56939016341512, 1.57623870273591,
- 1.58310172339603, 1.58997987002419, 1.59687379442279, 1.60378415602609,
- 1.61071162236983, 1.61765686957301, 1.62462058283303, 1.63160345693487,
- 1.63860619677555, 1.64562951790478, 1.65267414708306, 1.65974082285818,
- 1.66683029616166, 1.67394333092612, 1.68108070472517, 1.68824320943719,
- 1.69543165193456, 1.70264685479992, 1.7098896570713, 1.71716091501782,
- 1.72446150294804, 1.73179231405296, 1.73915426128591, 1.74654827828172,
- 1.75397532031767, 1.76143636531891, 1.76893241491127, 1.77646449552452,
- 1.78403365954944, 1.79164098655216, 1.79928758454972, 1.80697459135082,
- 1.81470317596628, 1.82247454009388, 1.83028991968276, 1.83815058658281,
- 1.84605785028518, 1.8540130597602, 1.86201760539967, 1.87007292107127,
- 1.878180486293, 1.88634182853678, 1.8945585256707, 1.90283220855043,
- 1.91116456377125, 1.91955733659319, 1.92801233405266, 1.93653142827569,
- 1.94511656000868, 1.95376974238465, 1.96249306494436, 1.97128869793366,
- 1.98015889690048, 1.98910600761744, 1.99813247135842, 2.00724083056053,
- 2.0164337349062, 2.02571394786385, 2.03508435372962, 2.04454796521753,
- 2.05410793165065, 2.06376754781173, 2.07353026351874, 2.0833996939983,
- 2.09337963113879, 2.10347405571488, 2.11368715068665, 2.12402331568952,
- 2.13448718284602, 2.14508363404789, 2.15581781987674, 2.16669518035431,
- 2.17772146774029, 2.18890277162636, 2.20024554661128, 2.21175664288416,
- 2.22344334009251, 2.23531338492992, 2.24737503294739, 2.25963709517379,
- 2.27210899022838, 2.28480080272449, 2.29772334890286, 2.31088825060137,
- 2.32430801887113, 2.33799614879653, 2.35196722737914, 2.36623705671729,
- 2.38082279517208, 2.39574311978193, 2.41101841390112, 2.42667098493715,
- 2.44272531820036, 2.4592083743347, 2.47614993967052, 2.49358304127105,
- 2.51154444162669, 2.53007523215985, 2.54922155032478, 2.56903545268184,
- 2.58957598670829, 2.61091051848882, 2.63311639363158, 2.65628303757674,
- 2.68051464328574, 2.70593365612306, 2.73268535904401, 2.76094400527999,
- 2.79092117400193, 2.82287739682644, 2.85713873087322, 2.89412105361341,
- 2.93436686720889, 2.97860327988184, 3.02783779176959, 3.08352613200214,
- 3.147889289518, 3.2245750520478, 3.32024473383983, 3.44927829856143,
- 3.65415288536101, 3.91075795952492 };
-
- real_T u;
- static const real_T dv2[257] = { 1.0, 0.977101701267673, 0.959879091800108,
- 0.9451989534423, 0.932060075959231, 0.919991505039348, 0.908726440052131,
- 0.898095921898344, 0.887984660755834, 0.878309655808918, 0.869008688036857,
- 0.860033621196332, 0.851346258458678, 0.842915653112205, 0.834716292986884,
- 0.826726833946222, 0.818929191603703, 0.811307874312656, 0.803849483170964,
- 0.796542330422959, 0.789376143566025, 0.782341832654803, 0.775431304981187,
- 0.768637315798486, 0.761953346836795, 0.755373506507096, 0.748892447219157,
- 0.742505296340151, 0.736207598126863, 0.729995264561476, 0.72386453346863,
- 0.717811932630722, 0.711834248878248, 0.705928501332754, 0.700091918136512,
- 0.694321916126117, 0.688616083004672, 0.682972161644995, 0.677388036218774,
- 0.671861719897082, 0.66639134390875, 0.660975147776663, 0.655611470579697,
- 0.650298743110817, 0.645035480820822, 0.639820277453057, 0.634651799287624,
- 0.629528779924837, 0.624450015547027, 0.619414360605834, 0.614420723888914,
- 0.609468064925773, 0.604555390697468, 0.599681752619125, 0.594846243767987,
- 0.590047996332826, 0.585286179263371, 0.580559996100791, 0.575868682972354,
- 0.571211506735253, 0.566587763256165, 0.561996775814525, 0.557437893618766,
- 0.552910490425833, 0.548413963255266, 0.543947731190026, 0.539511234256952,
- 0.535103932380458, 0.530725304403662, 0.526374847171684, 0.522052074672322,
- 0.517756517229756, 0.513487720747327, 0.509245245995748, 0.505028667943468,
- 0.500837575126149, 0.49667156905249, 0.492530263643869, 0.488413284705458,
- 0.484320269426683, 0.480250865909047, 0.476204732719506, 0.47218153846773,
- 0.468180961405694, 0.464202689048174, 0.460246417812843, 0.456311852678716,
- 0.452398706861849, 0.448506701507203, 0.444635565395739, 0.440785034665804,
- 0.436954852547985, 0.433144769112652, 0.429354541029442, 0.425583931338022,
- 0.421832709229496, 0.418100649837848, 0.414387534040891, 0.410693148270188,
- 0.407017284329473, 0.403359739221114, 0.399720314980197, 0.396098818515832,
- 0.392495061459315, 0.388908860018789, 0.385340034840077, 0.381788410873393,
- 0.378253817245619, 0.374736087137891, 0.371235057668239, 0.367750569779032,
- 0.364282468129004, 0.360830600989648, 0.357394820145781, 0.353974980800077,
- 0.350570941481406, 0.347182563956794, 0.343809713146851, 0.340452257044522,
- 0.337110066637006, 0.333783015830718, 0.330470981379163, 0.327173842813601,
- 0.323891482376391, 0.320623784956905, 0.317370638029914, 0.314131931596337,
- 0.310907558126286, 0.307697412504292, 0.30450139197665, 0.301319396100803,
- 0.298151326696685, 0.294997087799962, 0.291856585617095, 0.288729728482183,
- 0.285616426815502, 0.282516593083708, 0.279430141761638, 0.276356989295668,
- 0.273297054068577, 0.270250256365875, 0.267216518343561, 0.264195763997261,
- 0.261187919132721, 0.258192911337619, 0.255210669954662, 0.252241126055942,
- 0.249284212418529, 0.246339863501264, 0.24340801542275, 0.240488605940501,
- 0.237581574431238, 0.23468686187233, 0.231804410824339, 0.228934165414681,
- 0.226076071322381, 0.223230075763918, 0.220396127480152, 0.217574176724331,
- 0.214764175251174, 0.211966076307031, 0.209179834621125, 0.206405406397881,
- 0.203642749310335, 0.200891822494657, 0.198152586545776, 0.195425003514135,
- 0.192709036903589, 0.190004651670465, 0.187311814223801, 0.1846304924268,
- 0.181960655599523, 0.179302274522848, 0.176655321443735, 0.174019770081839,
- 0.171395595637506, 0.168782774801212, 0.166181285764482, 0.163591108232366,
- 0.161012223437511, 0.158444614155925, 0.15588826472448, 0.153343161060263,
- 0.150809290681846, 0.148286642732575, 0.145775208005994, 0.143274978973514,
- 0.140785949814445, 0.138308116448551, 0.135841476571254, 0.133386029691669,
- 0.130941777173644, 0.12850872228, 0.126086870220186, 0.123676228201597,
- 0.12127680548479, 0.11888861344291, 0.116511665625611, 0.114145977827839,
- 0.111791568163838, 0.109448457146812, 0.107116667774684, 0.104796225622487,
- 0.102487158941935, 0.10018949876881, 0.0979032790388625, 0.095628536713009,
- 0.093365311912691, 0.0911136480663738, 0.0888735920682759,
- 0.0866451944505581, 0.0844285095703535, 0.082223595813203,
- 0.0800305158146631, 0.0778493367020961, 0.0756801303589272,
- 0.0735229737139814, 0.0713779490588905, 0.0692451443970068,
- 0.0671246538277886, 0.065016577971243, 0.0629210244377582, 0.06083810834954,
- 0.0587679529209339, 0.0567106901062031, 0.0546664613248891,
- 0.0526354182767924, 0.0506177238609479, 0.0486135532158687,
- 0.0466230949019305, 0.0446465522512946, 0.0426841449164746,
- 0.0407361106559411, 0.0388027074045262, 0.0368842156885674,
- 0.0349809414617162, 0.0330932194585786, 0.0312214171919203,
- 0.0293659397581334, 0.0275272356696031, 0.0257058040085489,
- 0.0239022033057959, 0.0221170627073089, 0.0203510962300445,
- 0.0186051212757247, 0.0168800831525432, 0.0151770883079353,
- 0.0134974506017399, 0.0118427578579079, 0.0102149714397015,
- 0.00861658276939875, 0.00705087547137324, 0.00552240329925101,
- 0.00403797259336304, 0.00260907274610216, 0.0012602859304986,
- 0.000477467764609386 };
-
- real_T x;
- do {
- exitg1 = 0;
- genrand_uint32_vector(e_state, u32);
- i = (int32_T)((u32[1] >> 24U) + 1U);
- r = (((real_T)(u32[0] >> 3U) * 1.6777216E+7 + (real_T)((int32_T)u32[1] &
- 16777215)) * 2.2204460492503131E-16 - 1.0) * dv1[i];
- if (fabs(r) <= dv1[i - 1]) {
- exitg1 = 1;
- } else if (i < 256) {
- u = b_genrandu(e_state);
- if (dv2[i] + u * (dv2[i - 1] - dv2[i]) < exp(-0.5 * r * r)) {
- exitg1 = 1;
- }
- } else {
- do {
- u = b_genrandu(e_state);
- x = log(u) * 0.273661237329758;
- u = b_genrandu(e_state);
- } while (!(-2.0 * log(u) > x * x));
-
- if (r < 0.0) {
- r = x - 3.65415288536101;
- } else {
- r = 3.65415288536101 - x;
- }
-
- exitg1 = 1;
- }
- } while (exitg1 == 0);
-
- return r;
-}
-
-static real_T eml_rand_shr3cong(uint32_T e_state[2])
-{
- real_T r;
- uint32_T icng;
- uint32_T jsr;
- uint32_T ui;
- int32_T j;
- static const real_T dv0[65] = { 0.340945, 0.4573146, 0.5397793, 0.6062427,
- 0.6631691, 0.7136975, 0.7596125, 0.8020356, 0.8417227, 0.8792102, 0.9148948,
- 0.9490791, 0.9820005, 1.0138492, 1.044781, 1.0749254, 1.1043917, 1.1332738,
- 1.161653, 1.189601, 1.2171815, 1.2444516, 1.2714635, 1.298265, 1.3249008,
- 1.3514125, 1.3778399, 1.4042211, 1.4305929, 1.4569915, 1.4834527, 1.5100122,
- 1.5367061, 1.5635712, 1.5906454, 1.617968, 1.6455802, 1.6735255, 1.7018503,
- 1.7306045, 1.7598422, 1.7896223, 1.8200099, 1.851077, 1.8829044, 1.9155831,
- 1.9492166, 1.9839239, 2.0198431, 2.0571356, 2.095993, 2.136645, 2.1793713,
- 2.2245175, 2.2725186, 2.3239338, 2.3795008, 2.4402218, 2.5075117, 2.5834658,
- 2.6713916, 2.7769942, 2.7769942, 2.7769942, 2.7769942 };
-
- real_T x;
- real_T y;
- real_T s;
- icng = 69069U * e_state[0] + 1234567U;
- jsr = e_state[1] ^ e_state[1] << 13U;
- jsr ^= jsr >> 17U;
- jsr ^= jsr << 5U;
- ui = icng + jsr;
- j = (int32_T)(ui & 63U);
- r = (real_T)(int32_T)ui * 4.6566128730773926E-10 * dv0[j + 1];
- if (fabs(r) <= dv0[j]) {
- } else {
- x = (fabs(r) - dv0[j]) / (dv0[j + 1] - dv0[j]);
- icng = 69069U * icng + 1234567U;
- jsr ^= jsr << 13U;
- jsr ^= jsr >> 17U;
- jsr ^= jsr << 5U;
- y = (real_T)(int32_T)(icng + jsr) * 2.328306436538696E-10;
- s = x + (0.5 + y);
- if (s > 1.301198) {
- if (r < 0.0) {
- r = 0.4878992 * x - 0.4878992;
- } else {
- r = 0.4878992 - 0.4878992 * x;
- }
- } else if (s <= 0.9689279) {
- } else {
- s = 0.4878992 * x;
- x = 0.4878992 - 0.4878992 * x;
- if (0.5 + y > 12.67706 - 12.37586 * exp(-0.5 * (0.4878992 - s) * x)) {
- if (r < 0.0) {
- r = -(0.4878992 - s);
- } else {
- r = 0.4878992 - s;
- }
- } else if (exp(-0.5 * dv0[j + 1] * dv0[j + 1]) + (0.5 + y) * 0.01958303 /
- dv0[j + 1] <= exp(-0.5 * r * r)) {
- } else {
- do {
- icng = 69069U * icng + 1234567U;
- jsr ^= jsr << 13U;
- jsr ^= jsr >> 17U;
- jsr ^= jsr << 5U;
- x = log(0.5 + (real_T)(int32_T)(icng + jsr) * 2.328306436538696E-10) /
- 2.776994;
- icng = 69069U * icng + 1234567U;
- jsr ^= jsr << 13U;
- jsr ^= jsr >> 17U;
- jsr ^= jsr << 5U;
- } while (!(-2.0 * log(0.5 + (real_T)(int32_T)(icng + jsr) *
- 2.328306436538696E-10) > x * x));
-
- if (r < 0.0) {
- r = x - 2.776994;
- } else {
- r = 2.776994 - x;
- }
- }
- }
- }
-
- e_state[0] = icng;
- e_state[1] = jsr;
- return r;
-}
-
-static void genrand_uint32_vector(uint32_T mt[625], uint32_T u[2])
-{
- int32_T i;
- uint32_T mti;
- int32_T kk;
- uint32_T y;
- uint32_T b_y;
- uint32_T c_y;
- uint32_T d_y;
- for (i = 0; i < 2; i++) {
- u[i] = 0U;
- }
-
- for (i = 0; i < 2; i++) {
- mti = mt[624] + 1U;
- if (mti >= 625U) {
- for (kk = 0; kk < 227; kk++) {
- y = (mt[kk] & 2147483648U) | (mt[1 + kk] & 2147483647U);
- if ((int32_T)(y & 1U) == 0) {
- b_y = y >> 1U;
- } else {
- b_y = y >> 1U ^ 2567483615U;
- }
-
- mt[kk] = mt[397 + kk] ^ b_y;
- }
-
- for (kk = 0; kk < 396; kk++) {
- y = (mt[227 + kk] & 2147483648U) | (mt[228 + kk] & 2147483647U);
- if ((int32_T)(y & 1U) == 0) {
- c_y = y >> 1U;
- } else {
- c_y = y >> 1U ^ 2567483615U;
- }
-
- mt[227 + kk] = mt[kk] ^ c_y;
- }
-
- y = (mt[623] & 2147483648U) | (mt[0] & 2147483647U);
- if ((int32_T)(y & 1U) == 0) {
- d_y = y >> 1U;
- } else {
- d_y = y >> 1U ^ 2567483615U;
- }
-
- mt[623] = mt[396] ^ d_y;
- mti = 1U;
- }
-
- y = mt[(int32_T)mti - 1];
- mt[624] = mti;
- y ^= y >> 11U;
- y ^= y << 7U & 2636928640U;
- y ^= y << 15U & 4022730752U;
- y ^= y >> 18U;
- u[i] = y;
- }
-}
-
-static void genrandu(uint32_T s, uint32_T *e_state, real_T *r)
-{
- int32_T hi;
- uint32_T test1;
- uint32_T test2;
- hi = (int32_T)(s / 127773U);
- test1 = 16807U * (s - (uint32_T)hi * 127773U);
- test2 = 2836U * (uint32_T)hi;
- if (test1 < test2) {
- *e_state = (test1 - test2) + 2147483647U;
- } else {
- *e_state = test1 - test2;
- }
-
- *r = (real_T)*e_state * 4.6566128752457969E-10;
-}
-
-static void twister_state_vector(uint32_T mt[625], real_T seed)
-{
- uint32_T r;
- int32_T mti;
- if (seed < 4.294967296E+9) {
- if (seed >= 0.0) {
- r = (uint32_T)seed;
- } else {
- r = 0U;
- }
- } else if (seed >= 4.294967296E+9) {
- r = MAX_uint32_T;
- } else {
- r = 0U;
- }
-
- mt[0] = r;
- for (mti = 0; mti < 623; mti++) {
- r = (r ^ r >> 30U) * 1812433253U + (uint32_T)(1 + mti);
- mt[1 + mti] = r;
- }
-
- mt[624] = 624U;
-}
-
-real_T randn(void)
-{
- real_T r;
- uint32_T e_state;
- real_T t;
- real_T b_r;
- uint32_T f_state;
- if (method == 0U) {
- if (b_method == 4U) {
- do {
- genrandu(b_state, &e_state, &r);
- genrandu(e_state, &b_state, &t);
- b_r = 2.0 * r - 1.0;
- t = 2.0 * t - 1.0;
- t = t * t + b_r * b_r;
- } while (!(t <= 1.0));
-
- r = (2.0 * r - 1.0) * sqrt(-2.0 * log(t) / t);
- } else if (b_method == 5U) {
- r = eml_rand_shr3cong(c_state);
- } else {
- if (!state_not_empty) {
- memset(&d_state[0], 0, 625U * sizeof(uint32_T));
- twister_state_vector(d_state, 5489.0);
- state_not_empty = TRUE;
- }
-
- r = eml_rand_mt19937ar(d_state);
- }
- } else if (method == 4U) {
- e_state = state[0];
- do {
- genrandu(e_state, &f_state, &r);
- genrandu(f_state, &e_state, &t);
- b_r = 2.0 * r - 1.0;
- t = 2.0 * t - 1.0;
- t = t * t + b_r * b_r;
- } while (!(t <= 1.0));
-
- state[0] = e_state;
- r = (2.0 * r - 1.0) * sqrt(-2.0 * log(t) / t);
- } else {
- r = eml_rand_shr3cong(state);
- }
-
- return r;
-}
-
-/* End of code generation (randn.c) */
diff --git a/src/modules/position_estimator_mc/codegen/randn.h b/src/modules/position_estimator_mc/codegen/randn.h
deleted file mode 100755
index 8a2aa9277..000000000
--- a/src/modules/position_estimator_mc/codegen/randn.h
+++ /dev/null
@@ -1,33 +0,0 @@
-/*
- * randn.h
- *
- * Code generation for function 'randn'
- *
- * C source code generated on: Tue Feb 19 15:26:32 2013
- *
- */
-
-#ifndef __RANDN_H__
-#define __RANDN_H__
-/* Include files */
-#include <math.h>
-#include <stddef.h>
-#include <stdlib.h>
-#include <string.h>
-#include "rt_nonfinite.h"
-
-#include "rtwtypes.h"
-#include "kalman_dlqe3_types.h"
-
-/* Type Definitions */
-
-/* Named Constants */
-
-/* Variable Declarations */
-
-/* Variable Definitions */
-
-/* Function Declarations */
-extern real_T randn(void);
-#endif
-/* End of code generation (randn.h) */
diff --git a/src/modules/position_estimator_mc/codegen/rtGetInf.c b/src/modules/position_estimator_mc/codegen/rtGetInf.c
deleted file mode 100755
index c6fa7884e..000000000
--- a/src/modules/position_estimator_mc/codegen/rtGetInf.c
+++ /dev/null
@@ -1,139 +0,0 @@
-/*
- * rtGetInf.c
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-/*
- * Abstract:
- * MATLAB for code generation function to initialize non-finite, Inf and MinusInf
- */
-#include "rtGetInf.h"
-#define NumBitsPerChar 8U
-
-/* Function: rtGetInf ==================================================
- * Abstract:
- * Initialize rtInf needed by the generated code.
- * Inf is initialized as non-signaling. Assumes IEEE.
- */
-real_T rtGetInf(void)
-{
- size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
- real_T inf = 0.0;
- if (bitsPerReal == 32U) {
- inf = rtGetInfF();
- } else {
- uint16_T one = 1U;
- enum {
- LittleEndian,
- BigEndian
- } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
- switch (machByteOrder) {
- case LittleEndian:
- {
- union {
- LittleEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0x7FF00000U;
- tmpVal.bitVal.words.wordL = 0x00000000U;
- inf = tmpVal.fltVal;
- break;
- }
-
- case BigEndian:
- {
- union {
- BigEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0x7FF00000U;
- tmpVal.bitVal.words.wordL = 0x00000000U;
- inf = tmpVal.fltVal;
- break;
- }
- }
- }
-
- return inf;
-}
-
-/* Function: rtGetInfF ==================================================
- * Abstract:
- * Initialize rtInfF needed by the generated code.
- * Inf is initialized as non-signaling. Assumes IEEE.
- */
-real32_T rtGetInfF(void)
-{
- IEEESingle infF;
- infF.wordL.wordLuint = 0x7F800000U;
- return infF.wordL.wordLreal;
-}
-
-/* Function: rtGetMinusInf ==================================================
- * Abstract:
- * Initialize rtMinusInf needed by the generated code.
- * Inf is initialized as non-signaling. Assumes IEEE.
- */
-real_T rtGetMinusInf(void)
-{
- size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
- real_T minf = 0.0;
- if (bitsPerReal == 32U) {
- minf = rtGetMinusInfF();
- } else {
- uint16_T one = 1U;
- enum {
- LittleEndian,
- BigEndian
- } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
- switch (machByteOrder) {
- case LittleEndian:
- {
- union {
- LittleEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0xFFF00000U;
- tmpVal.bitVal.words.wordL = 0x00000000U;
- minf = tmpVal.fltVal;
- break;
- }
-
- case BigEndian:
- {
- union {
- BigEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0xFFF00000U;
- tmpVal.bitVal.words.wordL = 0x00000000U;
- minf = tmpVal.fltVal;
- break;
- }
- }
- }
-
- return minf;
-}
-
-/* Function: rtGetMinusInfF ==================================================
- * Abstract:
- * Initialize rtMinusInfF needed by the generated code.
- * Inf is initialized as non-signaling. Assumes IEEE.
- */
-real32_T rtGetMinusInfF(void)
-{
- IEEESingle minfF;
- minfF.wordL.wordLuint = 0xFF800000U;
- return minfF.wordL.wordLreal;
-}
-
-/* End of code generation (rtGetInf.c) */
diff --git a/src/modules/position_estimator_mc/codegen/rtGetInf.h b/src/modules/position_estimator_mc/codegen/rtGetInf.h
deleted file mode 100755
index e7b2a2d1c..000000000
--- a/src/modules/position_estimator_mc/codegen/rtGetInf.h
+++ /dev/null
@@ -1,23 +0,0 @@
-/*
- * rtGetInf.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-#ifndef __RTGETINF_H__
-#define __RTGETINF_H__
-
-#include <stddef.h>
-#include "rtwtypes.h"
-#include "rt_nonfinite.h"
-
-extern real_T rtGetInf(void);
-extern real32_T rtGetInfF(void);
-extern real_T rtGetMinusInf(void);
-extern real32_T rtGetMinusInfF(void);
-
-#endif
-/* End of code generation (rtGetInf.h) */
diff --git a/src/modules/position_estimator_mc/codegen/rtGetNaN.c b/src/modules/position_estimator_mc/codegen/rtGetNaN.c
deleted file mode 100755
index 552770149..000000000
--- a/src/modules/position_estimator_mc/codegen/rtGetNaN.c
+++ /dev/null
@@ -1,96 +0,0 @@
-/*
- * rtGetNaN.c
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-/*
- * Abstract:
- * MATLAB for code generation function to initialize non-finite, NaN
- */
-#include "rtGetNaN.h"
-#define NumBitsPerChar 8U
-
-/* Function: rtGetNaN ==================================================
- * Abstract:
- * Initialize rtNaN needed by the generated code.
- * NaN is initialized as non-signaling. Assumes IEEE.
- */
-real_T rtGetNaN(void)
-{
- size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
- real_T nan = 0.0;
- if (bitsPerReal == 32U) {
- nan = rtGetNaNF();
- } else {
- uint16_T one = 1U;
- enum {
- LittleEndian,
- BigEndian
- } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
- switch (machByteOrder) {
- case LittleEndian:
- {
- union {
- LittleEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0xFFF80000U;
- tmpVal.bitVal.words.wordL = 0x00000000U;
- nan = tmpVal.fltVal;
- break;
- }
-
- case BigEndian:
- {
- union {
- BigEndianIEEEDouble bitVal;
- real_T fltVal;
- } tmpVal;
-
- tmpVal.bitVal.words.wordH = 0x7FFFFFFFU;
- tmpVal.bitVal.words.wordL = 0xFFFFFFFFU;
- nan = tmpVal.fltVal;
- break;
- }
- }
- }
-
- return nan;
-}
-
-/* Function: rtGetNaNF ==================================================
- * Abstract:
- * Initialize rtNaNF needed by the generated code.
- * NaN is initialized as non-signaling. Assumes IEEE.
- */
-real32_T rtGetNaNF(void)
-{
- IEEESingle nanF = { { 0 } };
- uint16_T one = 1U;
- enum {
- LittleEndian,
- BigEndian
- } machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
- switch (machByteOrder) {
- case LittleEndian:
- {
- nanF.wordL.wordLuint = 0xFFC00000U;
- break;
- }
-
- case BigEndian:
- {
- nanF.wordL.wordLuint = 0x7FFFFFFFU;
- break;
- }
- }
-
- return nanF.wordL.wordLreal;
-}
-
-/* End of code generation (rtGetNaN.c) */
diff --git a/src/modules/position_estimator_mc/codegen/rtGetNaN.h b/src/modules/position_estimator_mc/codegen/rtGetNaN.h
deleted file mode 100755
index 5acdd9790..000000000
--- a/src/modules/position_estimator_mc/codegen/rtGetNaN.h
+++ /dev/null
@@ -1,21 +0,0 @@
-/*
- * rtGetNaN.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-#ifndef __RTGETNAN_H__
-#define __RTGETNAN_H__
-
-#include <stddef.h>
-#include "rtwtypes.h"
-#include "rt_nonfinite.h"
-
-extern real_T rtGetNaN(void);
-extern real32_T rtGetNaNF(void);
-
-#endif
-/* End of code generation (rtGetNaN.h) */
diff --git a/src/modules/position_estimator_mc/codegen/rt_nonfinite.c b/src/modules/position_estimator_mc/codegen/rt_nonfinite.c
deleted file mode 100755
index de121c4a0..000000000
--- a/src/modules/position_estimator_mc/codegen/rt_nonfinite.c
+++ /dev/null
@@ -1,87 +0,0 @@
-/*
- * rt_nonfinite.c
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-/*
- * Abstract:
- * MATLAB for code generation function to initialize non-finites,
- * (Inf, NaN and -Inf).
- */
-#include "rt_nonfinite.h"
-#include "rtGetNaN.h"
-#include "rtGetInf.h"
-
-real_T rtInf;
-real_T rtMinusInf;
-real_T rtNaN;
-real32_T rtInfF;
-real32_T rtMinusInfF;
-real32_T rtNaNF;
-
-/* Function: rt_InitInfAndNaN ==================================================
- * Abstract:
- * Initialize the rtInf, rtMinusInf, and rtNaN needed by the
- * generated code. NaN is initialized as non-signaling. Assumes IEEE.
- */
-void rt_InitInfAndNaN(size_t realSize)
-{
- (void) (realSize);
- rtNaN = rtGetNaN();
- rtNaNF = rtGetNaNF();
- rtInf = rtGetInf();
- rtInfF = rtGetInfF();
- rtMinusInf = rtGetMinusInf();
- rtMinusInfF = rtGetMinusInfF();
-}
-
-/* Function: rtIsInf ==================================================
- * Abstract:
- * Test if value is infinite
- */
-boolean_T rtIsInf(real_T value)
-{
- return ((value==rtInf || value==rtMinusInf) ? 1U : 0U);
-}
-
-/* Function: rtIsInfF =================================================
- * Abstract:
- * Test if single-precision value is infinite
- */
-boolean_T rtIsInfF(real32_T value)
-{
- return(((value)==rtInfF || (value)==rtMinusInfF) ? 1U : 0U);
-}
-
-/* Function: rtIsNaN ==================================================
- * Abstract:
- * Test if value is not a number
- */
-boolean_T rtIsNaN(real_T value)
-{
-#if defined(_MSC_VER) && (_MSC_VER <= 1200)
- return _isnan(value)? TRUE:FALSE;
-#else
- return (value!=value)? 1U:0U;
-#endif
-}
-
-/* Function: rtIsNaNF =================================================
- * Abstract:
- * Test if single-precision value is not a number
- */
-boolean_T rtIsNaNF(real32_T value)
-{
-#if defined(_MSC_VER) && (_MSC_VER <= 1200)
- return _isnan((real_T)value)? true:false;
-#else
- return (value!=value)? 1U:0U;
-#endif
-}
-
-
-/* End of code generation (rt_nonfinite.c) */
diff --git a/src/modules/position_estimator_mc/codegen/rt_nonfinite.h b/src/modules/position_estimator_mc/codegen/rt_nonfinite.h
deleted file mode 100755
index 3bbcfd087..000000000
--- a/src/modules/position_estimator_mc/codegen/rt_nonfinite.h
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * rt_nonfinite.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-#ifndef __RT_NONFINITE_H__
-#define __RT_NONFINITE_H__
-
-#if defined(_MSC_VER) && (_MSC_VER <= 1200)
-#include <float.h>
-#endif
-#include <stddef.h>
-#include "rtwtypes.h"
-
-extern real_T rtInf;
-extern real_T rtMinusInf;
-extern real_T rtNaN;
-extern real32_T rtInfF;
-extern real32_T rtMinusInfF;
-extern real32_T rtNaNF;
-extern void rt_InitInfAndNaN(size_t realSize);
-extern boolean_T rtIsInf(real_T value);
-extern boolean_T rtIsInfF(real32_T value);
-extern boolean_T rtIsNaN(real_T value);
-extern boolean_T rtIsNaNF(real32_T value);
-
-typedef struct {
- struct {
- uint32_T wordH;
- uint32_T wordL;
- } words;
-} BigEndianIEEEDouble;
-
-typedef struct {
- struct {
- uint32_T wordL;
- uint32_T wordH;
- } words;
-} LittleEndianIEEEDouble;
-
-typedef struct {
- union {
- real32_T wordLreal;
- uint32_T wordLuint;
- } wordL;
-} IEEESingle;
-
-#endif
-/* End of code generation (rt_nonfinite.h) */
diff --git a/src/modules/position_estimator_mc/codegen/rtwtypes.h b/src/modules/position_estimator_mc/codegen/rtwtypes.h
deleted file mode 100755
index 8916e8572..000000000
--- a/src/modules/position_estimator_mc/codegen/rtwtypes.h
+++ /dev/null
@@ -1,159 +0,0 @@
-/*
- * rtwtypes.h
- *
- * Code generation for function 'kalman_dlqe2'
- *
- * C source code generated on: Thu Feb 14 12:52:29 2013
- *
- */
-
-#ifndef __RTWTYPES_H__
-#define __RTWTYPES_H__
-#ifndef TRUE
-# define TRUE (1U)
-#endif
-#ifndef FALSE
-# define FALSE (0U)
-#endif
-#ifndef __TMWTYPES__
-#define __TMWTYPES__
-
-#include <limits.h>
-
-/*=======================================================================*
- * Target hardware information
- * Device type: Generic->MATLAB Host Computer
- * Number of bits: char: 8 short: 16 int: 32
- * long: 32 native word size: 32
- * Byte ordering: LittleEndian
- * Signed integer division rounds to: Undefined
- * Shift right on a signed integer as arithmetic shift: off
- *=======================================================================*/
-
-/*=======================================================================*
- * Fixed width word size data types: *
- * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
- * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
- * real32_T, real64_T - 32 and 64 bit floating point numbers *
- *=======================================================================*/
-
-typedef signed char int8_T;
-typedef unsigned char uint8_T;
-typedef short int16_T;
-typedef unsigned short uint16_T;
-typedef int int32_T;
-typedef unsigned int uint32_T;
-typedef float real32_T;
-typedef double real64_T;
-
-/*===========================================================================*
- * Generic type definitions: real_T, time_T, boolean_T, int_T, uint_T, *
- * ulong_T, char_T and byte_T. *
- *===========================================================================*/
-
-typedef double real_T;
-typedef double time_T;
-typedef unsigned char boolean_T;
-typedef int int_T;
-typedef unsigned int uint_T;
-typedef unsigned long ulong_T;
-typedef char char_T;
-typedef char_T byte_T;
-
-/*===========================================================================*
- * Complex number type definitions *
- *===========================================================================*/
-#define CREAL_T
- typedef struct {
- real32_T re;
- real32_T im;
- } creal32_T;
-
- typedef struct {
- real64_T re;
- real64_T im;
- } creal64_T;
-
- typedef struct {
- real_T re;
- real_T im;
- } creal_T;
-
- typedef struct {
- int8_T re;
- int8_T im;
- } cint8_T;
-
- typedef struct {
- uint8_T re;
- uint8_T im;
- } cuint8_T;
-
- typedef struct {
- int16_T re;
- int16_T im;
- } cint16_T;
-
- typedef struct {
- uint16_T re;
- uint16_T im;
- } cuint16_T;
-
- typedef struct {
- int32_T re;
- int32_T im;
- } cint32_T;
-
- typedef struct {
- uint32_T re;
- uint32_T im;
- } cuint32_T;
-
-
-/*=======================================================================*
- * Min and Max: *
- * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
- * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
- *=======================================================================*/
-
-#define MAX_int8_T ((int8_T)(127))
-#define MIN_int8_T ((int8_T)(-128))
-#define MAX_uint8_T ((uint8_T)(255))
-#define MIN_uint8_T ((uint8_T)(0))
-#define MAX_int16_T ((int16_T)(32767))
-#define MIN_int16_T ((int16_T)(-32768))
-#define MAX_uint16_T ((uint16_T)(65535))
-#define MIN_uint16_T ((uint16_T)(0))
-#define MAX_int32_T ((int32_T)(2147483647))
-#define MIN_int32_T ((int32_T)(-2147483647-1))
-#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU))
-#define MIN_uint32_T ((uint32_T)(0))
-
-/* Logical type definitions */
-#if !defined(__cplusplus) && !defined(__true_false_are_keywords)
-# ifndef false
-# define false (0U)
-# endif
-# ifndef true
-# define true (1U)
-# endif
-#endif
-
-/*
- * MATLAB for code generation assumes the code is compiled on a target using a 2's compliment representation
- * for signed integer values.
- */
-#if ((SCHAR_MIN + 1) != -SCHAR_MAX)
-#error "This code must be compiled using a 2's complement representation for signed integer values"
-#endif
-
-/*
- * Maximum length of a MATLAB identifier (function/variable)
- * including the null-termination character. Referenced by
- * rt_logging.c and rt_matrx.c.
- */
-#define TMW_NAME_LENGTH_MAX 64
-
-#endif
-#endif
-/* End of code generation (rtwtypes.h) */
diff --git a/src/modules/position_estimator_mc/kalman_dlqe1.m b/src/modules/position_estimator_mc/kalman_dlqe1.m
deleted file mode 100755
index ff939d029..000000000
--- a/src/modules/position_estimator_mc/kalman_dlqe1.m
+++ /dev/null
@@ -1,3 +0,0 @@
-function [x_aposteriori] = kalman_dlqe1(A,C,K,x_aposteriori_k,z)
- x_aposteriori=A*x_aposteriori_k+K*(z-C*A*x_aposteriori_k);
-end \ No newline at end of file
diff --git a/src/modules/position_estimator_mc/kalman_dlqe2.m b/src/modules/position_estimator_mc/kalman_dlqe2.m
deleted file mode 100755
index 2a50164ef..000000000
--- a/src/modules/position_estimator_mc/kalman_dlqe2.m
+++ /dev/null
@@ -1,9 +0,0 @@
-function [x_aposteriori] = kalman_dlqe2(dt,k1,k2,k3,x_aposteriori_k,z)
- st = 1/2*dt^2;
- A = [1,dt,st;
- 0,1,dt;
- 0,0,1];
- C=[1,0,0];
- K = [k1;k2;k3];
- x_aposteriori=A*x_aposteriori_k+K*(z-C*A*x_aposteriori_k);
-end \ No newline at end of file
diff --git a/src/modules/position_estimator_mc/kalman_dlqe3.m b/src/modules/position_estimator_mc/kalman_dlqe3.m
deleted file mode 100755
index 4c6421b7f..000000000
--- a/src/modules/position_estimator_mc/kalman_dlqe3.m
+++ /dev/null
@@ -1,17 +0,0 @@
-function [x_aposteriori] = kalman_dlqe3(dt,k1,k2,k3,x_aposteriori_k,z,posUpdate,addNoise,sigma)
- st = 1/2*dt^2;
- A = [1,dt,st;
- 0,1,dt;
- 0,0,1];
- C=[1,0,0];
- K = [k1;k2;k3];
- if addNoise==1
- noise = sigma*randn(1,1);
- z = z + noise;
- end
- if(posUpdate)
- x_aposteriori=A*x_aposteriori_k+K*(z-C*A*x_aposteriori_k);
- else
- x_aposteriori=A*x_aposteriori_k;
- end
-end \ No newline at end of file
diff --git a/src/modules/position_estimator_mc/module.mk b/src/modules/position_estimator_mc/module.mk
deleted file mode 100644
index 40b135ea4..000000000
--- a/src/modules/position_estimator_mc/module.mk
+++ /dev/null
@@ -1,60 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# Makefile to build the position estimator
-#
-
-MODULE_COMMAND = position_estimator_mc
-
-SRCS = position_estimator_mc_main.c \
- position_estimator_mc_params.c \
- codegen/positionKalmanFilter1D_initialize.c \
- codegen/positionKalmanFilter1D_terminate.c \
- codegen/positionKalmanFilter1D.c \
- codegen/rt_nonfinite.c \
- codegen/rtGetInf.c \
- codegen/rtGetNaN.c \
- codegen/positionKalmanFilter1D_dT_initialize.c \
- codegen/positionKalmanFilter1D_dT_terminate.c \
- codegen/kalman_dlqe1.c \
- codegen/kalman_dlqe1_initialize.c \
- codegen/kalman_dlqe1_terminate.c \
- codegen/kalman_dlqe2.c \
- codegen/kalman_dlqe2_initialize.c \
- codegen/kalman_dlqe2_terminate.c \
- codegen/kalman_dlqe3.c \
- codegen/kalman_dlqe3_initialize.c \
- codegen/kalman_dlqe3_terminate.c \
- codegen/kalman_dlqe3_data.c \
- codegen/randn.c
diff --git a/src/modules/position_estimator_mc/positionKalmanFilter1D.m b/src/modules/position_estimator_mc/positionKalmanFilter1D.m
deleted file mode 100755
index 144ff8c7c..000000000
--- a/src/modules/position_estimator_mc/positionKalmanFilter1D.m
+++ /dev/null
@@ -1,19 +0,0 @@
-function [x_aposteriori,P_aposteriori]=positionKalmanFilter1D(A,B,C,x_aposteriori_k,P_aposteriori_k,u,z,gps_update,Q,R,thresh,decay)
-%prediction
- x_apriori=A*x_aposteriori_k+B*u;
- P_apriori=A*P_aposteriori_k*A'+Q;
- if abs(u)<thresh
- x_apriori(2)=decay*x_apriori(2);
- end
- %update
- if gps_update==1
- y=z-C*x_apriori;
- S=C*P_apriori*C'+R;
- K=(P_apriori*C')/S;
- x_aposteriori=x_apriori+K*y;
- P_aposteriori=(eye(size(P_apriori))-K*C)*P_apriori;
- else
- x_aposteriori=x_apriori;
- P_aposteriori=P_apriori;
- end
-end
diff --git a/src/modules/position_estimator_mc/positionKalmanFilter1D_dT.m b/src/modules/position_estimator_mc/positionKalmanFilter1D_dT.m
deleted file mode 100755
index f94cce1fb..000000000
--- a/src/modules/position_estimator_mc/positionKalmanFilter1D_dT.m
+++ /dev/null
@@ -1,26 +0,0 @@
-function [x_aposteriori,P_aposteriori]=positionKalmanFilter1D_dT(dT,x_aposteriori_k,P_aposteriori_k,u,z,gps_update,Q,R,thresh,decay)
- %dynamics
- A = [1 dT -0.5*dT*dT;
- 0 1 -dT;
- 0 0 1];
- B = [0.5*dT*dT; dT; 0];
- C = [1 0 0];
- %prediction
- x_apriori=A*x_aposteriori_k+B*u;
- P_apriori=A*P_aposteriori_k*A'+Q;
- if abs(u)<thresh
- x_apriori(2)=decay*x_apriori(2);
- end
- %update
- if gps_update==1
- y=z-C*x_apriori;
- S=C*P_apriori*C'+R;
- K=(P_apriori*C')/S;
- x_aposteriori=x_apriori+K*y;
- P_aposteriori=(eye(size(P_apriori))-K*C)*P_apriori;
- else
- x_aposteriori=x_apriori;
- P_aposteriori=P_apriori;
- end
-end
-
diff --git a/src/modules/position_estimator_mc/position_estimator_mc_main.c b/src/modules/position_estimator_mc/position_estimator_mc_main.c
deleted file mode 100755
index 363961819..000000000
--- a/src/modules/position_estimator_mc/position_estimator_mc_main.c
+++ /dev/null
@@ -1,515 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Damian Aregger <daregger@student.ethz.ch>
- * Tobias Naegeli <naegelit@student.ethz.ch>
-* Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file position_estimator_main.c
- * Model-identification based position estimator for multirotors
- */
-
-#include <unistd.h>
-#include <stdlib.h>
-#include <stdio.h>
-#include <stdbool.h>
-#include <fcntl.h>
-#include <float.h>
-#include <string.h>
-#include <nuttx/config.h>
-#include <nuttx/sched.h>
-#include <sys/prctl.h>
-#include <termios.h>
-#include <errno.h>
-#include <limits.h>
-#include <math.h>
-#include <uORB/uORB.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/parameter_update.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/actuator_outputs.h>
-#include <uORB/topics/actuator_controls_effective.h>
-#include <uORB/topics/vehicle_status.h>
-#include <uORB/topics/vehicle_vicon_position.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_local_position_setpoint.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <mavlink/mavlink_log.h>
-#include <poll.h>
-#include <systemlib/geo/geo.h>
-#include <systemlib/err.h>
-#include <systemlib/systemlib.h>
-
-#include <drivers/drv_hrt.h>
-
-#include "position_estimator_mc_params.h"
-//#include <uORB/topics/debug_key_value.h>
-#include "codegen/kalman_dlqe2.h"
-#include "codegen/kalman_dlqe2_initialize.h"
-#include "codegen/kalman_dlqe3.h"
-#include "codegen/kalman_dlqe3_initialize.h"
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int position_estimator_mc_task; /**< Handle of deamon task / thread */
-
-__EXPORT int position_estimator_mc_main(int argc, char *argv[]);
-
-int position_estimator_mc_thread_main(int argc, char *argv[]);
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- warnx("%s\n", reason);
- warnx("usage: position_estimator_mc {start|stop|status}");
- exit(1);
-}
-
-/**
- * The position_estimator_mc_thread only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int position_estimator_mc_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("position_estimator_mc already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- position_estimator_mc_task = task_spawn_cmd("position_estimator_mc",
- SCHED_RR,
- SCHED_PRIORITY_MAX - 5,
- 4096,
- position_estimator_mc_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- warnx("position_estimator_mc is running");
- } else {
- warnx("position_estimator_mc not started");
- }
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-/****************************************************************************
- * main
- ****************************************************************************/
-int position_estimator_mc_thread_main(int argc, char *argv[])
-{
- /* welcome user */
- warnx("[position_estimator_mc] started");
- int mavlink_fd;
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
- mavlink_log_info(mavlink_fd, "[position_estimator_mc] started");
-
- /* initialize values */
- float z[3] = {0, 0, 0}; /* output variables from tangent plane mapping */
- // float rotMatrix[4] = {1.0f, 0.0f, 0.0f, 1.0f};
- float x_x_aposteriori_k[3] = {1.0f, 0.0f, 0.0f};
- float x_y_aposteriori_k[3] = {1.0f, 0.0f, 0.0f};
- float x_z_aposteriori_k[3] = {1.0f, 0.0f, 0.0f};
- float x_x_aposteriori[3] = {0.0f, 0.0f, 0.0f};
- float x_y_aposteriori[3] = {1.0f, 0.0f, 0.0f};
- float x_z_aposteriori[3] = {1.0f, 0.0f, 0.0f};
-
- // XXX this is terribly wrong and should actual dT instead
- const float dT_const_50 = 1.0f/50.0f;
-
- float addNoise = 0.0f;
- float sigma = 0.0f;
- //computed from dlqe in matlab
- const float K_vicon_50Hz[3] = {0.5297f, 0.9873f, 0.9201f};
- // XXX implement baro filter
- const float K_baro[3] = {0.0248f, 0.0377f, 0.0287f};
- float K[3] = {0.0f, 0.0f, 0.0f};
- int baro_loop_cnt = 0;
- int baro_loop_end = 70; /* measurement for 1 second */
- float p0_Pa = 0.0f; /* to determin while start up */
- float rho0 = 1.293f; /* standard pressure */
- const float const_earth_gravity = 9.81f;
-
- float posX = 0.0f;
- float posY = 0.0f;
- float posZ = 0.0f;
-
- double lat_current;
- double lon_current;
- float alt_current;
-
- float gps_origin_altitude = 0.0f;
-
- /* Initialize filter */
- kalman_dlqe2_initialize();
- kalman_dlqe3_initialize();
-
- /* declare and safely initialize all structs */
- struct sensor_combined_s sensor;
- memset(&sensor, 0, sizeof(sensor));
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- struct vehicle_status_s vehicle_status;
- memset(&vehicle_status, 0, sizeof(vehicle_status)); /* make sure that baroINITdone = false */
- struct vehicle_vicon_position_s vicon_pos;
- memset(&vicon_pos, 0, sizeof(vicon_pos));
- struct actuator_controls_effective_s act_eff;
- memset(&act_eff, 0, sizeof(act_eff));
- struct vehicle_gps_position_s gps;
- memset(&gps, 0, sizeof(gps));
- struct vehicle_local_position_s local_pos_est;
- memset(&local_pos_est, 0, sizeof(local_pos_est));
- struct vehicle_global_position_s global_pos_est;
- memset(&global_pos_est, 0, sizeof(global_pos_est));
-
- /* subscribe */
- int sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- int sub_params = orb_subscribe(ORB_ID(parameter_update));
- int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- int vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
- int actuator_eff_sub = orb_subscribe(ORB_ID(actuator_controls_effective_0));
- int vehicle_gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
-
- /* advertise */
- orb_advert_t local_pos_est_pub = 0;
- orb_advert_t global_pos_est_pub = 0;
-
- struct position_estimator_mc_params pos1D_params;
- struct position_estimator_mc_param_handles pos1D_param_handles;
- /* initialize parameter handles */
- parameters_init(&pos1D_param_handles);
-
- bool flag_use_gps = false;
- bool flag_use_baro = false;
- bool flag_baro_initialized = false; /* in any case disable baroINITdone */
- /* FIRST PARAMETER READ at START UP*/
- struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), sub_params, &update); /* read from param to clear updated flag */
- /* FIRST PARAMETER UPDATE */
- parameters_update(&pos1D_param_handles, &pos1D_params);
- flag_use_baro = pos1D_params.baro;
- sigma = pos1D_params.sigma;
- addNoise = pos1D_params.addNoise;
- /* END FIRST PARAMETER UPDATE */
-
- /* try to grab a vicon message - if it fails, go for GPS. */
-
- /* make sure the next orb_check() can't return true unless we get a timely update */
- orb_copy(ORB_ID(vehicle_vicon_position), vicon_pos_sub, &vicon_pos);
- /* allow 200 ms for vicon to come in */
- usleep(200000);
- /* check if we got vicon */
- bool update_check;
- orb_check(vicon_pos_sub, &update_check);
- /* if no update was available, use GPS */
- flag_use_gps = !update_check;
-
- if (flag_use_gps) {
- mavlink_log_info(mavlink_fd, "[pos_est_mc] GPS locked");
- /* wait until gps signal turns valid, only then can we initialize the projection */
-
- // XXX magic number
- float hdop_threshold_m = 4.0f;
- float vdop_threshold_m = 8.0f;
-
- /*
- * If horizontal dilution of precision (hdop / eph)
- * and vertical diluation of precision (vdop / epv)
- * are below a certain threshold (e.g. 4 m), AND
- * home position is not yet set AND the last GPS
- * GPS measurement is not older than two seconds AND
- * the system is currently not armed, set home
- * position to the current position.
- */
-
- while (!(gps.fix_type == 3
- && (gps.eph_m < hdop_threshold_m)
- && (gps.epv_m < vdop_threshold_m)
- && (hrt_absolute_time() - gps.timestamp_position < 2000000))) {
-
- struct pollfd fds1[2] = {
- { .fd = vehicle_gps_sub, .events = POLLIN },
- { .fd = sub_params, .events = POLLIN },
- };
-
- /* wait for GPS updates, BUT READ VEHICLE STATUS (!)
- * this choice is critical, since the vehicle status might not
- * actually change, if this app is started after GPS lock was
- * aquired.
- */
- if (poll(fds1, 2, 5000)) {
- if (fds1[0].revents & POLLIN){
- /* Read gps position */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- }
- if (fds1[1].revents & POLLIN){
- /* Read out parameters to check for an update there, e.g. useGPS variable */
- /* read from param to clear updated flag */
- struct parameter_update_s updated;
- orb_copy(ORB_ID(parameter_update), sub_params, &updated);
- /* update parameters */
- parameters_update(&pos1D_param_handles, &pos1D_params);
- }
- }
- static int printcounter = 0;
- if (printcounter == 100) {
- printcounter = 0;
- warnx("[pos_est_mc] wait for GPS fix");
- }
- printcounter++;
- }
-
- /* get gps value for first initialization */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- lat_current = ((double)(gps.lat)) * 1e-7d;
- lon_current = ((double)(gps.lon)) * 1e-7d;
- alt_current = gps.alt * 1e-3f;
- gps_origin_altitude = alt_current;
- /* initialize coordinates */
- map_projection_init(lat_current, lon_current);
- /* publish global position messages only after first GPS message */
- printf("[pos_est_mc] initialized projection with: lat: %.10f, lon:%.10f\n", lat_current, lon_current);
-
- } else {
- mavlink_log_info(mavlink_fd, "[pos_est_mc] I'm NOT using GPS - I use VICON");
- /* onboard calculated position estimations */
- }
- thread_running = true;
-
- struct pollfd fds2[3] = {
- { .fd = vehicle_gps_sub, .events = POLLIN },
- { .fd = vicon_pos_sub, .events = POLLIN },
- { .fd = sub_params, .events = POLLIN },
- };
-
- bool vicon_updated = false;
- bool gps_updated = false;
-
- /**< main_loop */
- while (!thread_should_exit) {
- int ret = poll(fds2, 3, 20); //wait maximal this 20 ms = 50 Hz minimum rate
- if (ret < 0) {
- /* poll error */
- } else {
- if (fds2[2].revents & POLLIN){
- /* new parameter */
- /* read from param to clear updated flag */
- struct parameter_update_s updated;
- orb_copy(ORB_ID(parameter_update), sub_params, &updated);
- /* update parameters */
- parameters_update(&pos1D_param_handles, &pos1D_params);
- flag_use_baro = pos1D_params.baro;
- sigma = pos1D_params.sigma;
- addNoise = pos1D_params.addNoise;
- }
- vicon_updated = false; /* default is no vicon_updated */
- if (fds2[1].revents & POLLIN) {
- /* new vicon position */
- orb_copy(ORB_ID(vehicle_vicon_position), vicon_pos_sub, &vicon_pos);
- posX = vicon_pos.x;
- posY = vicon_pos.y;
- posZ = vicon_pos.z;
- vicon_updated = true; /* set flag for vicon update */
- } /* end of poll call for vicon updates */
- gps_updated = false;
- if (fds2[0].revents & POLLIN) {
- /* new GPS value */
- orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_sub, &gps);
- /* Project gps lat lon (Geographic coordinate system) to plane*/
- map_projection_project(((double)(gps.lat)) * 1e-7d, ((double)(gps.lon)) * 1e-7d, &(z[0]), &(z[1]));
- posX = z[0];
- posY = z[1];
- posZ = (float)(gps.alt * 1e-3f);
- gps_updated = true;
- }
-
- /* Main estimator loop */
- orb_copy(ORB_ID(actuator_controls_effective_0), actuator_eff_sub, &act_eff);
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- orb_copy(ORB_ID(vehicle_status), vehicle_status_sub, &vehicle_status);
- orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensor);
- // barometric pressure estimation at start up
- if (!flag_baro_initialized){
- // mean calculation over several measurements
- if (baro_loop_cnt<baro_loop_end) {
- p0_Pa += (sensor.baro_pres_mbar*100);
- baro_loop_cnt++;
- } else {
- p0_Pa /= (float)(baro_loop_cnt);
- flag_baro_initialized = true;
- char *baro_m_start = "barometer initialized with p0 = ";
- char p0_char[15];
- sprintf(p0_char, "%8.2f", (double)(p0_Pa/100));
- char *baro_m_end = " mbar";
- char str[80];
- strcpy(str,baro_m_start);
- strcat(str,p0_char);
- strcat(str,baro_m_end);
- mavlink_log_info(mavlink_fd, str);
- }
- }
- if (flag_use_gps) {
- /* initialize map projection with the last estimate (not at full rate) */
- if (gps.fix_type > 2) {
- /* x-y-position/velocity estimation in earth frame = gps frame */
- kalman_dlqe3(dT_const_50,K_vicon_50Hz[0],K_vicon_50Hz[1],K_vicon_50Hz[2],x_x_aposteriori_k,posX,gps_updated,0.0f,0.0f,x_x_aposteriori);
- memcpy(x_x_aposteriori_k, x_x_aposteriori, sizeof(x_x_aposteriori));
- kalman_dlqe3(dT_const_50,K_vicon_50Hz[0],K_vicon_50Hz[1],K_vicon_50Hz[2],x_y_aposteriori_k,posY,gps_updated,0.0f,0.0f,x_y_aposteriori);
- memcpy(x_y_aposteriori_k, x_y_aposteriori, sizeof(x_y_aposteriori));
- /* z-position/velocity estimation in earth frame = vicon frame */
- float z_est = 0.0f;
- if (flag_baro_initialized && flag_use_baro) {
- z_est = -p0_Pa*logf(p0_Pa/(sensor.baro_pres_mbar*100))/(rho0*const_earth_gravity);
- K[0] = K_vicon_50Hz[0];
- K[1] = K_vicon_50Hz[1];
- K[2] = K_vicon_50Hz[2];
- gps_updated = 1.0f; /* always enable the update, cause baro update = 200 Hz */
- } else {
- z_est = posZ;
- K[0] = K_vicon_50Hz[0];
- K[1] = K_vicon_50Hz[1];
- K[2] = K_vicon_50Hz[2];
- }
-
- kalman_dlqe3(dT_const_50,K[0],K[1],K[2],x_z_aposteriori_k,z_est,gps_updated,0.0f,0.0f,x_z_aposteriori);
- memcpy(x_z_aposteriori_k, x_z_aposteriori, sizeof(x_z_aposteriori));
- local_pos_est.x = x_x_aposteriori_k[0];
- local_pos_est.vx = x_x_aposteriori_k[1];
- local_pos_est.y = x_y_aposteriori_k[0];
- local_pos_est.vy = x_y_aposteriori_k[1];
- local_pos_est.z = x_z_aposteriori_k[0];
- local_pos_est.vz = x_z_aposteriori_k[1];
- local_pos_est.timestamp = hrt_absolute_time();
- if ((isfinite(x_x_aposteriori_k[0])) && (isfinite(x_x_aposteriori_k[1])) && (isfinite(x_y_aposteriori_k[0])) && (isfinite(x_y_aposteriori_k[1])) && (isfinite(x_z_aposteriori_k[0])) && (isfinite(x_z_aposteriori_k[1]))) {
- /* publish local position estimate */
- if (local_pos_est_pub > 0) {
- orb_publish(ORB_ID(vehicle_local_position), local_pos_est_pub, &local_pos_est);
- } else {
- local_pos_est_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos_est);
- }
- /* publish on GPS updates */
- if (gps_updated) {
-
- double lat, lon;
- float alt = z_est + gps_origin_altitude;
-
- map_projection_reproject(local_pos_est.x, local_pos_est.y, &lat, &lon);
-
- global_pos_est.lat = lat;
- global_pos_est.lon = lon;
- global_pos_est.alt = alt;
-
- if (global_pos_est_pub > 0) {
- orb_publish(ORB_ID(vehicle_global_position), global_pos_est_pub, &global_pos_est);
- } else {
- global_pos_est_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_pos_est);
- }
- }
- }
- }
- } else {
- /* x-y-position/velocity estimation in earth frame = vicon frame */
- kalman_dlqe3(dT_const_50,K_vicon_50Hz[0],K_vicon_50Hz[1],K_vicon_50Hz[2],x_x_aposteriori_k,posX,vicon_updated,addNoise,sigma,x_x_aposteriori);
- memcpy(x_x_aposteriori_k, x_x_aposteriori, sizeof(x_x_aposteriori));
- kalman_dlqe3(dT_const_50,K_vicon_50Hz[0],K_vicon_50Hz[1],K_vicon_50Hz[2],x_y_aposteriori_k,posY,vicon_updated,addNoise,sigma,x_y_aposteriori);
- memcpy(x_y_aposteriori_k, x_y_aposteriori, sizeof(x_y_aposteriori));
- /* z-position/velocity estimation in earth frame = vicon frame */
- float z_est = 0.0f;
- float local_sigma = 0.0f;
- if (flag_baro_initialized && flag_use_baro) {
- z_est = -p0_Pa*logf(p0_Pa/(sensor.baro_pres_mbar*100.0f))/(rho0*const_earth_gravity);
- K[0] = K_vicon_50Hz[0];
- K[1] = K_vicon_50Hz[1];
- K[2] = K_vicon_50Hz[2];
- vicon_updated = 1; /* always enable the update, cause baro update = 200 Hz */
- local_sigma = 0.0f; /* don't add noise on barometer in any case */
- } else {
- z_est = posZ;
- K[0] = K_vicon_50Hz[0];
- K[1] = K_vicon_50Hz[1];
- K[2] = K_vicon_50Hz[2];
- local_sigma = sigma;
- }
- kalman_dlqe3(dT_const_50,K[0],K[1],K[2],x_z_aposteriori_k,z_est,vicon_updated,addNoise,local_sigma,x_z_aposteriori);
- memcpy(x_z_aposteriori_k, x_z_aposteriori, sizeof(x_z_aposteriori));
- local_pos_est.x = x_x_aposteriori_k[0];
- local_pos_est.vx = x_x_aposteriori_k[1];
- local_pos_est.y = x_y_aposteriori_k[0];
- local_pos_est.vy = x_y_aposteriori_k[1];
- local_pos_est.z = x_z_aposteriori_k[0];
- local_pos_est.vz = x_z_aposteriori_k[1];
- local_pos_est.timestamp = hrt_absolute_time();
- if ((isfinite(x_x_aposteriori_k[0])) && (isfinite(x_x_aposteriori_k[1])) && (isfinite(x_y_aposteriori_k[0])) && (isfinite(x_y_aposteriori_k[1])) && (isfinite(x_z_aposteriori_k[0])) && (isfinite(x_z_aposteriori_k[1]))){
- if(local_pos_est_pub > 0)
- orb_publish(ORB_ID(vehicle_local_position), local_pos_est_pub, &local_pos_est);
- else
- local_pos_est_pub = orb_advertise(ORB_ID(vehicle_local_position), &local_pos_est);
- //char buf[0xff]; sprintf(buf,"[pos_est_mc] x:%f, y:%f, z:%f",x_x_aposteriori_k[0],x_y_aposteriori_k[0],x_z_aposteriori_k[0]);
- //mavlink_log_info(mavlink_fd, buf);
- }
- }
- } /* end of poll return value check */
- }
-
- printf("[pos_est_mc] exiting.\n");
- mavlink_log_info(mavlink_fd, "[pos_est_mc] exiting");
- thread_running = false;
- return 0;
-}
diff --git a/src/modules/position_estimator_mc/position_estimator_mc_params.c b/src/modules/position_estimator_mc/position_estimator_mc_params.c
deleted file mode 100755
index 72e5bc73b..000000000
--- a/src/modules/position_estimator_mc/position_estimator_mc_params.c
+++ /dev/null
@@ -1,68 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Damian Aregger <daregger@student.ethz.ch>
- * Tobias Naegeli <naegelit@student.ethz.ch>
-* Lorenz Meier <lm@inf.ethz.ch>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/*
- * @file position_estimator_mc_params.c
- *
- * Parameters for position_estimator_mc
- */
-
-#include "position_estimator_mc_params.h"
-
-/* Kalman Filter covariances */
-/* gps measurement noise standard deviation */
-PARAM_DEFINE_FLOAT(POS_EST_ADDN, 1.0f);
-PARAM_DEFINE_FLOAT(POS_EST_SIGMA, 0.0f);
-PARAM_DEFINE_FLOAT(POS_EST_R, 1.0f);
-PARAM_DEFINE_INT32(POS_EST_BARO, 0.0f);
-
-int parameters_init(struct position_estimator_mc_param_handles *h)
-{
- h->addNoise = param_find("POS_EST_ADDN");
- h->sigma = param_find("POS_EST_SIGMA");
- h->r = param_find("POS_EST_R");
- h->baro_param_handle = param_find("POS_EST_BARO");
- return OK;
-}
-
-int parameters_update(const struct position_estimator_mc_param_handles *h, struct position_estimator_mc_params *p)
-{
- param_get(h->addNoise, &(p->addNoise));
- param_get(h->sigma, &(p->sigma));
- param_get(h->r, &(p->R));
- param_get(h->baro_param_handle, &(p->baro));
- return OK;
-}
diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c
index 56c5aa005..62e6b12cb 100644
--- a/src/modules/px4iofirmware/controls.c
+++ b/src/modules/px4iofirmware/controls.c
@@ -291,6 +291,7 @@ controls_tick() {
/* set RC OK flag, as we got an update */
r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_OK;
+ r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_OK;
/* if we have enough channels (5) to control the vehicle, the mapping is ok */
if (assigned_channels > 4) {
@@ -336,6 +337,9 @@ controls_tick() {
PX4IO_P_STATUS_FLAGS_OVERRIDE |
PX4IO_P_STATUS_FLAGS_RC_OK);
+ /* flag raw RC as lost */
+ r_raw_rc_flags &= ~(PX4IO_P_RAW_RC_FLAGS_RC_OK);
+
/* Mark all channels as invalid, as we just lost the RX */
r_rc_valid = 0;
@@ -405,8 +409,9 @@ ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len)
if (*num_values > PX4IO_RC_INPUT_CHANNELS)
*num_values = PX4IO_RC_INPUT_CHANNELS;
- for (unsigned i = 0; i < *num_values; i++)
+ for (unsigned i = 0; i < *num_values; i++) {
values[i] = ppm_buffer[i];
+ }
/* clear validity */
ppm_last_valid_decode = 0;
diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp
index 9558198f3..2f721bf1e 100644
--- a/src/modules/px4iofirmware/mixer.cpp
+++ b/src/modules/px4iofirmware/mixer.cpp
@@ -213,6 +213,7 @@ mixer_tick(void)
mixed = mixer_group.mix(&outputs[0], PX4IO_SERVO_COUNT);
in_mixer = false;
+ /* the pwm limit call takes care of out of band errors */
pwm_limit_calc(should_arm, mixed, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs, r_page_servos, &pwm_limit);
for (unsigned i = mixed; i < PX4IO_SERVO_COUNT; i++)
@@ -254,10 +255,25 @@ mixer_tick(void)
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
up_pwm_servo_set(i, r_page_servos[i]);
+ /* set S.BUS1 or S.BUS2 outputs */
+
+ if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) {
+ sbus2_output(r_page_servos, PX4IO_SERVO_COUNT);
+ } else if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) {
+ sbus1_output(r_page_servos, PX4IO_SERVO_COUNT);
+ }
+
} else if (mixer_servos_armed && should_always_enable_pwm) {
/* set the disarmed servo outputs. */
for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++)
up_pwm_servo_set(i, r_page_servo_disarmed[i]);
+
+ /* set S.BUS1 or S.BUS2 outputs */
+ if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT)
+ sbus1_output(r_page_servos, PX4IO_SERVO_COUNT);
+
+ if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT)
+ sbus2_output(r_page_servos, PX4IO_SERVO_COUNT);
}
}
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 6c20d6006..7471faec7 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -142,6 +142,7 @@
#define PX4IO_P_RAW_RC_FLAGS_FAILSAFE (1 << 1) /* receiver is in failsafe mode */
#define PX4IO_P_RAW_RC_FLAGS_RC_DSM11 (1 << 2) /* DSM decoding is 11 bit mode */
#define PX4IO_P_RAW_RC_FLAGS_MAPPING_OK (1 << 3) /* Channel mapping is ok */
+#define PX4IO_P_RAW_RC_FLAGS_RC_OK (1 << 4) /* RC reception ok */
#define PX4IO_P_RAW_RC_NRSSI 2 /* [2] Normalized RSSI value, 0: no reception, 255: perfect reception */
#define PX4IO_P_RAW_RC_DATA 3 /* [1] + [2] Details about the RC source (PPM frame length, Spektrum protocol type) */
@@ -189,6 +190,8 @@
#define PX4IO_P_SETUP_RELAYS_POWER2 (1<<1) /* hardware rev [1] power relay 2 */
#define PX4IO_P_SETUP_RELAYS_ACC1 (1<<2) /* hardware rev [1] accessory power 1 */
#define PX4IO_P_SETUP_RELAYS_ACC2 (1<<3) /* hardware rev [1] accessory power 2 */
+#else
+#define PX4IO_P_SETUP_RELAYS_PAD 5
#endif
#define PX4IO_P_SETUP_VBATT_SCALE 6 /* hardware rev [1] battery voltage correction factor (float) */
@@ -208,15 +211,16 @@ enum { /* DSM bind states */
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
- /* 12 occupied by CRC */
+ /* storage space of 12 occupied by CRC */
+#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
+ 'armed' (PWM enabled) state - this is a non-data write and
+ hence index 12 can safely be used. */
#define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */
-#define PX4IO_P_SETUP_FORCE_SAFETY_OFF 12 /* force safety switch into
- 'armed' (PWM enabled) state */
-#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
+#define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */
/* autopilot control values, -10000..10000 */
-#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
+#define PX4IO_PAGE_CONTROLS 51 /**< actuator control groups, one after the other, 8 wide */
#define PX4IO_P_CONTROLS_GROUP_0 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 0) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_1 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 1) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
#define PX4IO_P_CONTROLS_GROUP_2 (PX4IO_PROTOCOL_MAX_CONTROL_COUNT * 2) /**< 0..PX4IO_PROTOCOL_MAX_CONTROL_COUNT - 1 */
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 4db948484..ca175bfbc 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -219,6 +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);
/** 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 9e5d7e7e2..db1836f4a 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -160,6 +160,9 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_PWM_ALTRATE] = 200,
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
[PX4IO_P_SETUP_RELAYS] = 0,
+#else
+ /* this is unused, but we will pad it for readability (the compiler pads it automatically) */
+ [PX4IO_P_SETUP_RELAYS_PAD] = 0,
#endif
#ifdef ADC_VSERVO
[PX4IO_P_SETUP_VSERVO_SCALE] = 10000,
@@ -463,9 +466,18 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
#ifdef ENABLE_SBUS_OUT
ENABLE_SBUS_OUT(value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT));
- /* disable the conflicting options */
- if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) {
- value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | PX4IO_P_SETUP_FEATURES_ADC_RSSI);
+ /* disable the conflicting options with SBUS 1 */
+ if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI |
+ PX4IO_P_SETUP_FEATURES_ADC_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS2_OUT);
+ }
+
+ /* disable the conflicting options with SBUS 2 */
+ if (value & (PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) {
+ value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI |
+ PX4IO_P_SETUP_FEATURES_ADC_RSSI |
+ PX4IO_P_SETUP_FEATURES_SBUS1_OUT);
}
#endif
@@ -514,18 +526,22 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
break;
case PX4IO_P_SETUP_PWM_DEFAULTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, value, r_setup_pwm_altrate);
break;
case PX4IO_P_SETUP_PWM_ALTRATE:
- if (value < 50)
+ if (value < 50) {
value = 50;
- if (value > 400)
+ }
+ if (value > 400) {
value = 400;
+ }
pwm_configure_rates(r_setup_pwm_rates, r_setup_pwm_defaultrate, value);
break;
@@ -557,8 +573,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
// check the magic value
- if (value != PX4IO_REBOOT_BL_MAGIC)
+ if (value != PX4IO_REBOOT_BL_MAGIC) {
break;
+ }
// we schedule a reboot rather than rebooting
// immediately to allow the IO board to ACK
@@ -576,6 +593,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
}
break;
+ case PX4IO_P_SETUP_RC_THR_FAILSAFE_US:
+ if (value > 650 && value < 2350) {
+ r_page_setup[PX4IO_P_SETUP_RC_THR_FAILSAFE_US] = value;
+ }
+ break;
+
default:
return -1;
}
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index f6ec542eb..0e7dc621c 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -93,7 +93,7 @@ int
sbus_init(const char *device)
{
if (sbus_fd < 0)
- sbus_fd = open(device, O_RDONLY | O_NONBLOCK);
+ sbus_fd = open(device, O_RDWR | O_NONBLOCK);
if (sbus_fd >= 0) {
struct termios t;
@@ -113,11 +113,22 @@ sbus_init(const char *device)
} else {
debug("S.Bus: open failed");
}
-
return sbus_fd;
}
bool
+sbus1_output(uint16_t *values, uint16_t num_values)
+{
+ write(sbus_fd, 'A', 1);
+}
+
+bool
+sbus2_output(uint16_t *values, uint16_t num_values)
+{
+ write(sbus_fd, 'B', 1);
+}
+
+bool
sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels)
{
ssize_t ret;
diff --git a/src/modules/sdlog/module.mk b/src/modules/sdlog/module.mk
deleted file mode 100644
index 89da2d827..000000000
--- a/src/modules/sdlog/module.mk
+++ /dev/null
@@ -1,43 +0,0 @@
-############################################################################
-#
-# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# sdlog Application
-#
-
-MODULE_COMMAND = sdlog
-# The main thread only buffers to RAM, needs a high priority
-MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
-
-SRCS = sdlog.c \
- sdlog_ringbuffer.c
diff --git a/src/modules/sdlog/sdlog.c b/src/modules/sdlog/sdlog.c
deleted file mode 100644
index c22523bf2..000000000
--- a/src/modules/sdlog/sdlog.c
+++ /dev/null
@@ -1,840 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * 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 sdlog.c
- * @author Lorenz Meier <lm@inf.ethz.ch>
- *
- * Simple SD logger for flight data. Buffers new sensor values and
- * does the heavy SD I/O in a low-priority worker thread.
- */
-
-#include <nuttx/config.h>
-#include <sys/types.h>
-#include <sys/stat.h>
-#include <sys/prctl.h>
-#include <fcntl.h>
-#include <errno.h>
-#include <unistd.h>
-#include <stdio.h>
-#include <poll.h>
-#include <stdlib.h>
-#include <string.h>
-#include <ctype.h>
-#include <systemlib/err.h>
-#include <unistd.h>
-#include <drivers/drv_hrt.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/vehicle_attitude.h>
-#include <uORB/topics/vehicle_attitude_setpoint.h>
-#include <uORB/topics/actuator_outputs.h>
-#include <uORB/topics/actuator_controls.h>
-#include <uORB/topics/actuator_controls_effective.h>
-#include <uORB/topics/vehicle_command.h>
-#include <uORB/topics/vehicle_local_position.h>
-#include <uORB/topics/vehicle_global_position.h>
-#include <uORB/topics/vehicle_gps_position.h>
-#include <uORB/topics/vehicle_vicon_position.h>
-#include <uORB/topics/optical_flow.h>
-#include <uORB/topics/battery_status.h>
-#include <uORB/topics/differential_pressure.h>
-#include <uORB/topics/airspeed.h>
-
-#include <systemlib/systemlib.h>
-
-#include <mavlink/mavlink_log.h>
-
-#include "sdlog_ringbuffer.h"
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log folders */
-
-static const char *mountpoint = "/fs/microsd";
-static const char *mfile_in = "/etc/logging/logconv.m";
-int sysvector_file = -1;
-int mavlink_fd = -1;
-struct sdlog_logbuffer lb;
-
-/* mutex / condition to synchronize threads */
-pthread_mutex_t sysvector_mutex;
-pthread_cond_t sysvector_cond;
-
-/**
- * System state vector log buffer writing
- */
-static void *sdlog_sysvector_write_thread(void *arg);
-
-/**
- * Create the thread to write the system vector
- */
-pthread_t sysvector_write_start(struct sdlog_logbuffer *logbuf);
-
-/**
- * SD log management function.
- */
-__EXPORT int sdlog_main(int argc, char *argv[]);
-
-/**
- * Mainloop of sd log deamon.
- */
-int sdlog_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static int file_exist(const char *filename);
-
-static int file_copy(const char *file_old, const char *file_new);
-
-static void handle_command(struct vehicle_command_s *cmd);
-
-/**
- * Print the current status.
- */
-static void print_sdlog_status(void);
-
-/**
- * Create folder for current logging session.
- */
-static int create_logfolder(char *folder_path);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
-
- errx(1, "usage: sdlog {start|stop|status} [-s <number of skipped lines>]\n\n");
-}
-
-// XXX turn this into a C++ class
-unsigned sensor_combined_bytes = 0;
-unsigned actuator_outputs_bytes = 0;
-unsigned actuator_controls_bytes = 0;
-unsigned sysvector_bytes = 0;
-unsigned blackbox_file_bytes = 0;
-uint64_t starttime = 0;
-
-/* logging on or off, default to true */
-bool logging_enabled = true;
-
-/**
- * The sd log deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_spawn_cmd().
- */
-int sdlog_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("sdlog already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn_cmd("sdlog",
- SCHED_DEFAULT,
- SCHED_PRIORITY_DEFAULT - 30,
- 4096,
- sdlog_thread_main,
- (const char **)argv);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- if (!thread_running) {
- printf("\tsdlog is not started\n");
- }
-
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- print_sdlog_status();
-
- } else {
- printf("\tsdlog not started\n");
- }
-
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int create_logfolder(char *folder_path)
-{
- /* make folder on sdcard */
- uint16_t foldernumber = 1; // start with folder 0001
- int mkdir_ret;
-
- /* look for the next folder that does not exist */
- while (foldernumber < MAX_NO_LOGFOLDER) {
- /* set up file path: e.g. /mnt/sdcard/sensorfile0001.txt */
- sprintf(folder_path, "%s/session%04u", mountpoint, foldernumber);
- mkdir_ret = mkdir(folder_path, S_IRWXU | S_IRWXG | S_IRWXO);
- /* the result is -1 if the folder exists */
-
- if (mkdir_ret == 0) {
- /* folder does not exist, success */
-
- /* now copy the Matlab/Octave file */
- char mfile_out[100];
- sprintf(mfile_out, "%s/session%04u/run_to_plot_data.m", mountpoint, foldernumber);
- int ret = file_copy(mfile_in, mfile_out);
-
- if (!ret) {
- warnx("copied m file to %s", mfile_out);
-
- } else {
- warnx("failed copying m file from %s to\n %s", mfile_in, mfile_out);
- }
-
- break;
-
- } else if (mkdir_ret == -1) {
- /* folder exists already */
- foldernumber++;
- continue;
-
- } else {
- warn("failed creating new folder");
- return -1;
- }
- }
-
- if (foldernumber >= MAX_NO_LOGFOLDER) {
- /* we should not end up here, either we have more than MAX_NO_LOGFOLDER on the SD card, or another problem */
- warn("all %d possible folders exist already", MAX_NO_LOGFOLDER);
- return -1;
- }
-
- return 0;
-}
-
-
-static void *
-sdlog_sysvector_write_thread(void *arg)
-{
- /* set name */
- prctl(PR_SET_NAME, "sdlog microSD I/O", 0);
-
- struct sdlog_logbuffer *logbuf = (struct sdlog_logbuffer *)arg;
-
- int poll_count = 0;
- struct sdlog_sysvector sysvect;
- memset(&sysvect, 0, sizeof(sysvect));
-
- while (!thread_should_exit) {
-
- /* make sure threads are synchronized */
- pthread_mutex_lock(&sysvector_mutex);
-
- /* only wait if no data is available to process */
- if (sdlog_logbuffer_is_empty(logbuf)) {
- /* blocking wait for new data at this line */
- pthread_cond_wait(&sysvector_cond, &sysvector_mutex);
- }
-
- /* only quickly load data, do heavy I/O a few lines down */
- int ret = sdlog_logbuffer_read(logbuf, &sysvect);
- /* continue */
- pthread_mutex_unlock(&sysvector_mutex);
-
- if (ret == OK) {
- sysvector_bytes += write(sysvector_file, (const char *)&sysvect, sizeof(sysvect));
- }
-
- if (poll_count % 100 == 0) {
- fsync(sysvector_file);
- }
-
- poll_count++;
- }
-
- fsync(sysvector_file);
-
- return OK;
-}
-
-pthread_t
-sysvector_write_start(struct sdlog_logbuffer *logbuf)
-{
- pthread_attr_t receiveloop_attr;
- pthread_attr_init(&receiveloop_attr);
-
- struct sched_param param;
- /* low priority, as this is expensive disk I/O */
- param.sched_priority = SCHED_PRIORITY_DEFAULT - 40;
- (void)pthread_attr_setschedparam(&receiveloop_attr, &param);
-
- pthread_attr_setstacksize(&receiveloop_attr, 2048);
-
- pthread_t thread;
- pthread_create(&thread, &receiveloop_attr, sdlog_sysvector_write_thread, logbuf);
- return thread;
-
- // XXX we have to destroy the attr at some point
-}
-
-
-int sdlog_thread_main(int argc, char *argv[])
-{
- mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
-
- if (mavlink_fd < 0) {
- warnx("ERROR: Failed to open MAVLink log stream, start mavlink app first.\n");
- }
-
- /* log every n'th value (skip three per default) */
- int skip_value = 3;
-
- /* work around some stupidity in task_create's argv handling */
- argc -= 2;
- argv += 2;
- int ch;
-
- while ((ch = getopt(argc, argv, "s:r")) != EOF) {
- switch (ch) {
- case 's':
- {
- /* log only every n'th (gyro clocked) value */
- unsigned s = strtoul(optarg, NULL, 10);
-
- if (s < 1 || s > 250) {
- errx(1, "Wrong skip value of %d, out of range (1..250)\n", s);
- } else {
- skip_value = s;
- }
- }
- break;
-
- case 'r':
- /* log only on request, disable logging per default */
- logging_enabled = false;
- break;
-
- case '?':
- if (optopt == 'c') {
- warnx("Option -%c requires an argument.\n", optopt);
- } else if (isprint(optopt)) {
- warnx("Unknown option `-%c'.\n", optopt);
- } else {
- warnx("Unknown option character `\\x%x'.\n", optopt);
- }
-
- default:
- usage("unrecognized flag");
- errx(1, "exiting.");
- }
- }
-
- if (file_exist(mountpoint) != OK) {
- errx(1, "logging mount point %s not present, exiting.", mountpoint);
- }
-
- char folder_path[64];
-
- if (create_logfolder(folder_path))
- errx(1, "unable to create logging folder, exiting.");
-
- FILE *gpsfile;
- FILE *blackbox_file;
-
- /* string to hold the path to the sensorfile */
- char path_buf[64] = "";
-
- /* only print logging path, important to find log file later */
- warnx("logging to directory %s\n", folder_path);
-
- /* set up file path: e.g. /mnt/sdcard/session0001/actuator_controls0.bin */
- sprintf(path_buf, "%s/%s.bin", folder_path, "sysvector");
-
- if (0 == (sysvector_file = open(path_buf, O_CREAT | O_WRONLY | O_DSYNC))) {
- errx(1, "opening %s failed.\n", path_buf);
- }
-
- /* set up file path: e.g. /mnt/sdcard/session0001/gps.txt */
- sprintf(path_buf, "%s/%s.txt", folder_path, "gps");
-
- if (NULL == (gpsfile = fopen(path_buf, "w"))) {
- errx(1, "opening %s failed.\n", path_buf);
- }
-
- int gpsfile_no = fileno(gpsfile);
-
- /* set up file path: e.g. /mnt/sdcard/session0001/blackbox.txt */
- sprintf(path_buf, "%s/%s.txt", folder_path, "blackbox");
-
- if (NULL == (blackbox_file = fopen(path_buf, "w"))) {
- errx(1, "opening %s failed.\n", path_buf);
- }
-
- // XXX for fsync() calls
- int blackbox_file_no = fileno(blackbox_file);
-
- /* --- IMPORTANT: DEFINE NUMBER OF ORB STRUCTS TO WAIT FOR HERE --- */
- /* number of messages */
- const ssize_t fdsc = 25;
- /* Sanity check variable and index */
- ssize_t fdsc_count = 0;
- /* file descriptors to wait for */
- struct pollfd fds[fdsc];
-
-
- struct {
- struct sensor_combined_s raw;
- struct vehicle_attitude_s att;
- struct vehicle_attitude_setpoint_s att_sp;
- struct actuator_outputs_s act_outputs;
- struct actuator_controls_s act_controls;
- struct actuator_controls_effective_s act_controls_effective;
- struct vehicle_command_s cmd;
- struct vehicle_local_position_s local_pos;
- struct vehicle_global_position_s global_pos;
- struct vehicle_gps_position_s gps_pos;
- struct vehicle_vicon_position_s vicon_pos;
- struct optical_flow_s flow;
- struct battery_status_s batt;
- struct differential_pressure_s diff_pres;
- struct airspeed_s airspeed;
- } buf;
- memset(&buf, 0, sizeof(buf));
-
- struct {
- int cmd_sub;
- int sensor_sub;
- int att_sub;
- int spa_sub;
- int act_0_sub;
- int controls_0_sub;
- int controls_effective_0_sub;
- int local_pos_sub;
- int global_pos_sub;
- int gps_pos_sub;
- int vicon_pos_sub;
- int flow_sub;
- int batt_sub;
- int diff_pres_sub;
- int airspeed_sub;
- } subs;
-
- /* --- MANAGEMENT - LOGGING COMMAND --- */
- /* subscribe to ORB for vehicle command */
- subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
- fds[fdsc_count].fd = subs.cmd_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GPS POSITION --- */
- /* subscribe to ORB for global position */
- subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
- fds[fdsc_count].fd = subs.gps_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- SENSORS RAW VALUE --- */
- /* subscribe to ORB for sensors raw */
- subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined));
- fds[fdsc_count].fd = subs.sensor_sub;
- /* do not rate limit, instead use skip counter (aliasing on rate limit) */
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ATTITUDE VALUE --- */
- /* subscribe to ORB for attitude */
- subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
- fds[fdsc_count].fd = subs.att_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ATTITUDE SETPOINT VALUE --- */
- /* subscribe to ORB for attitude setpoint */
- /* struct already allocated */
- subs.spa_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
- fds[fdsc_count].fd = subs.spa_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /** --- ACTUATOR OUTPUTS --- */
- subs.act_0_sub = orb_subscribe(ORB_ID(actuator_outputs_0));
- fds[fdsc_count].fd = subs.act_0_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ACTUATOR CONTROL VALUE --- */
- /* subscribe to ORB for actuator control */
- subs.controls_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
- fds[fdsc_count].fd = subs.controls_0_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- ACTUATOR CONTROL EFFECTIVE VALUE --- */
- /* subscribe to ORB for actuator control */
- subs.controls_effective_0_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE);
- fds[fdsc_count].fd = subs.controls_effective_0_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- LOCAL POSITION --- */
- /* subscribe to ORB for local position */
- subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- fds[fdsc_count].fd = subs.local_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- GLOBAL POSITION --- */
- /* subscribe to ORB for global position */
- subs.global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
- fds[fdsc_count].fd = subs.global_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- VICON POSITION --- */
- /* subscribe to ORB for vicon position */
- subs.vicon_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
- fds[fdsc_count].fd = subs.vicon_pos_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- FLOW measurements --- */
- /* subscribe to ORB for flow measurements */
- subs.flow_sub = orb_subscribe(ORB_ID(optical_flow));
- fds[fdsc_count].fd = subs.flow_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- BATTERY STATUS --- */
- /* subscribe to ORB for flow measurements */
- subs.batt_sub = orb_subscribe(ORB_ID(battery_status));
- fds[fdsc_count].fd = subs.batt_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- DIFFERENTIAL PRESSURE --- */
- /* subscribe to ORB for flow measurements */
- subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure));
- fds[fdsc_count].fd = subs.diff_pres_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* --- AIRSPEED --- */
- /* subscribe to ORB for airspeed */
- subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed));
- fds[fdsc_count].fd = subs.airspeed_sub;
- fds[fdsc_count].events = POLLIN;
- fdsc_count++;
-
- /* WARNING: If you get the error message below,
- * then the number of registered messages (fdsc)
- * differs from the number of messages in the above list.
- */
- if (fdsc_count > fdsc) {
- warn("WARNING: Not enough space for poll fds allocated. Check %s:%d.\n", __FILE__, __LINE__);
- fdsc_count = fdsc;
- }
-
- /*
- * set up poll to block for new data,
- * wait for a maximum of 1000 ms (1 second)
- */
- // const int timeout = 1000;
-
- thread_running = true;
-
- /* initialize log buffer with a size of 10 */
- sdlog_logbuffer_init(&lb, 10);
-
- /* initialize thread synchronization */
- pthread_mutex_init(&sysvector_mutex, NULL);
- pthread_cond_init(&sysvector_cond, NULL);
-
- /* start logbuffer emptying thread */
- pthread_t sysvector_pthread = sysvector_write_start(&lb);
-
- starttime = hrt_absolute_time();
-
- /* track skipping */
- int skip_count = 0;
-
- while (!thread_should_exit) {
-
- /* only poll for commands, gps and sensor_combined */
- int poll_ret = poll(fds, 3, 1000);
-
- /* handle the poll result */
- if (poll_ret == 0) {
- /* XXX this means none of our providers is giving us data - might be an error? */
- } else if (poll_ret < 0) {
- /* XXX this is seriously bad - should be an emergency */
- } else {
-
- int ifds = 0;
-
- /* --- VEHICLE COMMAND VALUE --- */
- if (fds[ifds++].revents & POLLIN) {
- /* copy command into local buffer */
- orb_copy(ORB_ID(vehicle_command), subs.cmd_sub, &buf.cmd);
-
- /* always log to blackbox, even when logging disabled */
- blackbox_file_bytes += fprintf(blackbox_file, "[%10.4f\tVCMD] CMD #%d [%f\t%f\t%f\t%f\t%f\t%f\t%f]\n", hrt_absolute_time()/1000000.0d,
- buf.cmd.command, (double)buf.cmd.param1, (double)buf.cmd.param2, (double)buf.cmd.param3, (double)buf.cmd.param4,
- (double)buf.cmd.param5, (double)buf.cmd.param6, (double)buf.cmd.param7);
-
- handle_command(&buf.cmd);
- }
-
- /* --- VEHICLE GPS VALUE --- */
- if (fds[ifds++].revents & POLLIN) {
- /* copy gps position into local buffer */
- orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
-
- /* if logging disabled, continue */
- if (logging_enabled) {
-
- /* write KML line */
- }
- }
-
- /* --- SENSORS RAW VALUE --- */
- if (fds[ifds++].revents & POLLIN) {
-
- // /* copy sensors raw data into local buffer */
- // orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw);
- // /* write out */
- // sensor_combined_bytes += write(sensorfile, (const char*)&(buf.raw), sizeof(buf.raw));
-
- /* always copy sensors raw data into local buffer, since poll flags won't clear else */
- orb_copy(ORB_ID(sensor_combined), subs.sensor_sub, &buf.raw);
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, subs.controls_0_sub, &buf.act_controls);
- orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE, subs.controls_effective_0_sub, &buf.act_controls_effective);
- orb_copy(ORB_ID(actuator_outputs_0), subs.act_0_sub, &buf.act_outputs);
- orb_copy(ORB_ID(vehicle_attitude_setpoint), subs.spa_sub, &buf.att_sp);
- orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf.gps_pos);
- orb_copy(ORB_ID(vehicle_local_position), subs.local_pos_sub, &buf.local_pos);
- orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos);
- orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att);
- orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos);
- orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow);
- orb_copy(ORB_ID(differential_pressure), subs.diff_pres_sub, &buf.diff_pres);
- orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed);
- orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt);
-
- /* if skipping is on or logging is disabled, ignore */
- if (skip_count < skip_value || !logging_enabled) {
- skip_count++;
- /* do not log data */
- continue;
- } else {
- /* log data, reset */
- skip_count = 0;
- }
-
- struct sdlog_sysvector sysvect = {
- .timestamp = buf.raw.timestamp,
- .gyro = {buf.raw.gyro_rad_s[0], buf.raw.gyro_rad_s[1], buf.raw.gyro_rad_s[2]},
- .accel = {buf.raw.accelerometer_m_s2[0], buf.raw.accelerometer_m_s2[1], buf.raw.accelerometer_m_s2[2]},
- .mag = {buf.raw.magnetometer_ga[0], buf.raw.magnetometer_ga[1], buf.raw.magnetometer_ga[2]},
- .baro = buf.raw.baro_pres_mbar,
- .baro_alt = buf.raw.baro_alt_meter,
- .baro_temp = buf.raw.baro_temp_celcius,
- .control = {buf.act_controls.control[0], buf.act_controls.control[1], buf.act_controls.control[2], buf.act_controls.control[3]},
- .actuators = {
- buf.act_outputs.output[0], buf.act_outputs.output[1], buf.act_outputs.output[2], buf.act_outputs.output[3],
- buf.act_outputs.output[4], buf.act_outputs.output[5], buf.act_outputs.output[6], buf.act_outputs.output[7]
- },
- .vbat = buf.batt.voltage_v,
- .bat_current = buf.batt.current_a,
- .bat_discharged = buf.batt.discharged_mah,
- .adc = {buf.raw.adc_voltage_v[0], buf.raw.adc_voltage_v[1], buf.raw.adc_voltage_v[2], buf.raw.adc_voltage_v[3]},
- .local_position = {buf.local_pos.x, buf.local_pos.y, buf.local_pos.z},
- .gps_raw_position = {buf.gps_pos.lat, buf.gps_pos.lon, buf.gps_pos.alt},
- .attitude = {buf.att.pitch, buf.att.roll, buf.att.yaw},
- .rotMatrix = {buf.att.R[0][0], buf.att.R[0][1], buf.att.R[0][2], buf.att.R[1][0], buf.att.R[1][1], buf.att.R[1][2], buf.att.R[2][0], buf.att.R[2][1], buf.att.R[2][2]},
- .vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw},
- .control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]},
- .flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality},
- .diff_pressure = buf.diff_pres.differential_pressure_pa,
- .ind_airspeed = buf.airspeed.indicated_airspeed_m_s,
- .true_airspeed = buf.airspeed.true_airspeed_m_s
- };
-
- /* put into buffer for later IO */
- pthread_mutex_lock(&sysvector_mutex);
- sdlog_logbuffer_write(&lb, &sysvect);
- /* signal the other thread new data, but not yet unlock */
- if ((unsigned)lb.count > (lb.size / 2)) {
- /* only request write if several packets can be written at once */
- pthread_cond_signal(&sysvector_cond);
- }
- /* unlock, now the writer thread may run */
- pthread_mutex_unlock(&sysvector_mutex);
- }
-
- }
-
- }
-
- print_sdlog_status();
-
- /* wake up write thread one last time */
- pthread_mutex_lock(&sysvector_mutex);
- pthread_cond_signal(&sysvector_cond);
- /* unlock, now the writer thread may return */
- pthread_mutex_unlock(&sysvector_mutex);
-
- /* wait for write thread to return */
- (void)pthread_join(sysvector_pthread, NULL);
-
- pthread_mutex_destroy(&sysvector_mutex);
- pthread_cond_destroy(&sysvector_cond);
-
- warnx("exiting.\n\n");
-
- /* finish KML file */
- // XXX
- fclose(gpsfile);
- fclose(blackbox_file);
-
- thread_running = false;
-
- return 0;
-}
-
-void print_sdlog_status()
-{
- unsigned bytes = sysvector_bytes + sensor_combined_bytes + actuator_outputs_bytes + blackbox_file_bytes + actuator_controls_bytes;
- float mebibytes = bytes / 1024.0f / 1024.0f;
- float seconds = ((float)(hrt_absolute_time() - starttime)) / 1000000.0f;
-
- warnx("wrote %4.2f MiB (average %5.3f MiB/s).\n", (double)mebibytes, (double)(mebibytes / seconds));
-}
-
-/**
- * @return 0 if file exists
- */
-int file_exist(const char *filename)
-{
- struct stat buffer;
- return stat(filename, &buffer);
-}
-
-int file_copy(const char *file_old, const char *file_new)
-{
- FILE *source, *target;
- source = fopen(file_old, "r");
- int ret = 0;
-
- if (source == NULL) {
- warnx("failed opening input file to copy");
- return 1;
- }
-
- target = fopen(file_new, "w");
-
- if (target == NULL) {
- fclose(source);
- warnx("failed to open output file to copy");
- return 1;
- }
-
- char buf[128];
- int nread;
-
- while ((nread = fread(buf, 1, sizeof(buf), source)) > 0) {
- int ret = fwrite(buf, 1, nread, target);
-
- if (ret <= 0) {
- warnx("error writing file");
- ret = 1;
- break;
- }
- }
-
- fsync(fileno(target));
-
- fclose(source);
- fclose(target);
-
- return ret;
-}
-
-void handle_command(struct vehicle_command_s *cmd)
-{
- /* result of the command */
- uint8_t result = VEHICLE_CMD_RESULT_UNSUPPORTED;
-
- /* request to set different system mode */
- switch (cmd->command) {
-
- case VEHICLE_CMD_PREFLIGHT_STORAGE:
-
- if (((int)(cmd->param3)) == 1) {
-
- /* enable logging */
- mavlink_log_info(mavlink_fd, "[log] file:");
- mavlink_log_info(mavlink_fd, "logdir");
- logging_enabled = true;
- }
- if (((int)(cmd->param3)) == 0) {
-
- /* disable logging */
- mavlink_log_info(mavlink_fd, "[log] stopped.");
- logging_enabled = false;
- }
- break;
-
- default:
- /* silently ignore */
- break;
- }
-
-}
diff --git a/src/modules/sdlog/sdlog_ringbuffer.c b/src/modules/sdlog/sdlog_ringbuffer.c
deleted file mode 100644
index d7c8a4759..000000000
--- a/src/modules/sdlog/sdlog_ringbuffer.c
+++ /dev/null
@@ -1,91 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * 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 sdlog_log.c
- * MAVLink text logging.
- *
- * @author Lorenz Meier <lm@inf.ethz.ch>
- */
-
-#include <string.h>
-#include <stdlib.h>
-
-#include "sdlog_ringbuffer.h"
-
-void sdlog_logbuffer_init(struct sdlog_logbuffer *lb, int size)
-{
- lb->size = size;
- lb->start = 0;
- lb->count = 0;
- lb->elems = (struct sdlog_sysvector *)calloc(lb->size, sizeof(struct sdlog_sysvector));
-}
-
-int sdlog_logbuffer_is_full(struct sdlog_logbuffer *lb)
-{
- return lb->count == (int)lb->size;
-}
-
-int sdlog_logbuffer_is_empty(struct sdlog_logbuffer *lb)
-{
- return lb->count == 0;
-}
-
-
-// XXX make these functions thread-safe
-void sdlog_logbuffer_write(struct sdlog_logbuffer *lb, const struct sdlog_sysvector *elem)
-{
- int end = (lb->start + lb->count) % lb->size;
- memcpy(&(lb->elems[end]), elem, sizeof(struct sdlog_sysvector));
-
- if (sdlog_logbuffer_is_full(lb)) {
- lb->start = (lb->start + 1) % lb->size; /* full, overwrite */
-
- } else {
- ++lb->count;
- }
-}
-
-int sdlog_logbuffer_read(struct sdlog_logbuffer *lb, struct sdlog_sysvector *elem)
-{
- if (!sdlog_logbuffer_is_empty(lb)) {
- memcpy(elem, &(lb->elems[lb->start]), sizeof(struct sdlog_sysvector));
- lb->start = (lb->start + 1) % lb->size;
- --lb->count;
- return 0;
-
- } else {
- return 1;
- }
-}
diff --git a/src/modules/sdlog/sdlog_ringbuffer.h b/src/modules/sdlog/sdlog_ringbuffer.h
deleted file mode 100644
index b65916459..000000000
--- a/src/modules/sdlog/sdlog_ringbuffer.h
+++ /dev/null
@@ -1,91 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2013 PX4 Development Team. All rights reserved.
- * 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 sdlog_ringbuffer.h
- * microSD logging
- *
- * @author Lorenz Meier <lm@inf.ethz.ch>
- */
-
-#ifndef SDLOG_RINGBUFFER_H_
-#define SDLOG_RINGBUFFER_H_
-
-#pragma pack(push, 1)
-struct sdlog_sysvector {
- uint64_t timestamp; /**< time [us] */
- float gyro[3]; /**< [rad/s] */
- float accel[3]; /**< [m/s^2] */
- float mag[3]; /**< [gauss] */
- float baro; /**< pressure [millibar] */
- float baro_alt; /**< altitude above MSL [meter] */
- float baro_temp; /**< [degree celcius] */
- float control[4]; /**< roll, pitch, yaw [-1..1], thrust [0..1] */
- float actuators[8]; /**< motor 1-8, in motor units (PWM: 1000-2000,AR.Drone: 0-512) */
- float vbat; /**< battery voltage in [volt] */
- float bat_current; /**< battery discharge current */
- float bat_discharged; /**< discharged energy in mAh */
- float adc[4]; /**< ADC ports [volt] */
- float local_position[3]; /**< tangent plane mapping into x,y,z [m] */
- int32_t gps_raw_position[3]; /**< latitude [degrees] north, longitude [degrees] east, altitude above MSL [millimeter] */
- float attitude[3]; /**< roll, pitch, yaw [rad] */
- float rotMatrix[9]; /**< unitvectors */
- float vicon[6]; /**< Vicon ground truth x, y, z and roll, pitch, yaw */
- float control_effective[4]; /**< roll, pitch, yaw [-1..1], thrust [0..1] */
- float flow[6]; /**< flow raw x, y, flow metric x, y, flow ground dist, flow quality */
- float diff_pressure; /**< differential pressure */
- float ind_airspeed; /**< indicated airspeed */
- float true_airspeed; /**< true airspeed */
-};
-#pragma pack(pop)
-
-struct sdlog_logbuffer {
- unsigned int start;
- // unsigned int end;
- unsigned int size;
- int count;
- struct sdlog_sysvector *elems;
-};
-
-void sdlog_logbuffer_init(struct sdlog_logbuffer *lb, int size);
-
-int sdlog_logbuffer_is_full(struct sdlog_logbuffer *lb);
-
-int sdlog_logbuffer_is_empty(struct sdlog_logbuffer *lb);
-
-void sdlog_logbuffer_write(struct sdlog_logbuffer *lb, const struct sdlog_sysvector *elem);
-
-int sdlog_logbuffer_read(struct sdlog_logbuffer *lb, struct sdlog_sysvector *elem);
-
-#endif
diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk
index f53129688..a28d43e72 100644
--- a/src/modules/sdlog2/module.mk
+++ b/src/modules/sdlog2/module.mk
@@ -41,3 +41,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-30"
SRCS = sdlog2.c \
logbuffer.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index b74d4183b..577cadfbb 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -89,6 +89,7 @@
#include <systemlib/systemlib.h>
#include <systemlib/param/param.h>
+#include <systemlib/perf_counter.h>
#include <version/version.h>
#include <mavlink/mavlink_log.h>
@@ -97,6 +98,36 @@
#include "sdlog2_format.h"
#include "sdlog2_messages.h"
+/**
+ * Logging rate.
+ *
+ * A value of -1 indicates the commandline argument
+ * should be obeyed. A value of 0 sets the minimum rate,
+ * any other value is interpreted as rate in Hertz. This
+ * parameter is only read out before logging starts (which
+ * commonly is before arming).
+ *
+ * @min -1
+ * @max 1
+ * @group SD Logging
+ */
+PARAM_DEFINE_INT32(SDLOG_RATE, -1);
+
+/**
+ * Enable extended logging mode.
+ *
+ * A value of -1 indicates the commandline argument
+ * should be obeyed. A value of 0 disables extended
+ * logging mode, a value of 1 enables it. This
+ * parameter is only read out before logging starts
+ * (which commonly is before arming).
+ *
+ * @min -1
+ * @max 1
+ * @group SD Logging
+ */
+PARAM_DEFINE_INT32(SDLOG_EXT, -1);
+
#define LOGBUFFER_WRITE_AND_COUNT(_msg) if (logbuffer_write(&lb, &log_msg, LOG_PACKET_SIZE(_msg))) { \
log_msgs_written++; \
} else { \
@@ -112,12 +143,14 @@ static bool main_thread_should_exit = false; /**< Deamon exit flag */
static bool thread_running = false; /**< Deamon status flag */
static int deamon_task; /**< Handle of deamon task / thread */
static bool logwriter_should_exit = false; /**< Logwriter thread exit flag */
-static const int MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
-static const int MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
+static const unsigned MAX_NO_LOGFOLDER = 999; /**< Maximum number of log dirs */
+static const unsigned MAX_NO_LOGFILE = 999; /**< Maximum number of log files */
static const int LOG_BUFFER_SIZE_DEFAULT = 8192;
static const int MAX_WRITE_CHUNK = 512;
static const int MIN_BYTES_TO_WRITE = 512;
+static bool _extended_logging = false;
+
static const char *log_root = "/fs/microsd/log";
static int mavlink_fd = -1;
struct logbuffer_s lb;
@@ -218,6 +251,8 @@ static int create_log_dir(void);
*/
static int open_log_file(void);
+static int open_perf_file(const char* str);
+
static void
sdlog2_usage(const char *reason)
{
@@ -225,12 +260,13 @@ sdlog2_usage(const char *reason)
fprintf(stderr, "%s\n", reason);
}
- errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t\n"
+ errx(1, "usage: sdlog2 {start|stop|status} [-r <log rate>] [-b <buffer size>] -e -a -t -x\n"
"\t-r\tLog rate in Hz, 0 means unlimited rate\n"
"\t-b\tLog buffer size in KiB, default is 8\n"
"\t-e\tEnable logging by default (if not, can be started by command)\n"
"\t-a\tLog only when armed (can be still overriden by command)\n"
- "\t-t\tUse date/time for naming log directories and files\n");
+ "\t-t\tUse date/time for naming log directories and files\n"
+ "\t-x\tExtended logging");
}
/**
@@ -349,8 +385,8 @@ int create_log_dir()
int open_log_file()
{
/* string to hold the path to the log */
- char log_file_name[16] = "";
- char log_file_path[48] = "";
+ char log_file_name[32] = "";
+ char log_file_path[64] = "";
if (log_name_timestamp && gps_time != 0) {
/* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
@@ -378,7 +414,58 @@ int open_log_file()
if (file_number > MAX_NO_LOGFILE) {
/* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
- warnx("all %d possible files exist already", MAX_NO_LOGFILE);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
+ return -1;
+ }
+ }
+
+ int fd = open(log_file_path, O_CREAT | O_WRONLY | O_DSYNC);
+
+ if (fd < 0) {
+ warn("failed opening log: %s", log_file_name);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
+
+ } else {
+ warnx("log file: %s", log_file_name);
+ mavlink_log_info(mavlink_fd, "[sdlog2] log file: %s", log_file_name);
+ }
+
+ return fd;
+}
+
+int open_perf_file(const char* str)
+{
+ /* string to hold the path to the log */
+ char log_file_name[32] = "";
+ char log_file_path[64] = "";
+
+ if (log_name_timestamp && gps_time != 0) {
+ /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */
+ time_t gps_time_sec = gps_time / 1000000;
+ struct tm t;
+ gmtime_r(&gps_time_sec, &t);
+ strftime(log_file_name, sizeof(log_file_name), "perf%H_%M_%S.txt", &t);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
+
+ } else {
+ unsigned file_number = 1; // start with file log001
+
+ /* look for the next file that does not exist */
+ while (file_number <= MAX_NO_LOGFILE) {
+ /* format log file path: e.g. /fs/microsd/sess001/log001.bin */
+ snprintf(log_file_name, sizeof(log_file_name), "perf%03u.txt", file_number);
+ snprintf(log_file_path, sizeof(log_file_path), "%s/%s_%s", log_dir, str, log_file_name);
+
+ if (!file_exist(log_file_path)) {
+ break;
+ }
+
+ file_number++;
+ }
+
+ if (file_number > MAX_NO_LOGFILE) {
+ /* we should not end up here, either we have more than MAX_NO_LOGFILE on the SD card, or another problem */
+ mavlink_log_critical(mavlink_fd, "[sdlog2] ERR: max files %d", MAX_NO_LOGFILE);
return -1;
}
}
@@ -387,7 +474,7 @@ int open_log_file()
if (fd < 0) {
warn("failed opening log: %s", log_file_name);
- mavlink_log_info(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
+ mavlink_log_critical(mavlink_fd, "[sdlog2] failed opening log: %s", log_file_name);
} else {
warnx("log file: %s", log_file_name);
@@ -529,6 +616,12 @@ void sdlog2_start_log()
errx(1, "error creating logwriter thread");
}
+ /* write all performance counters */
+ int perf_fd = open_perf_file("preflight");
+ dprintf(perf_fd, "PERFORMANCE COUNTERS PRE-FLIGHT\n\n");
+ perf_print_all(perf_fd);
+ close(perf_fd);
+
logging_enabled = true;
}
@@ -556,6 +649,12 @@ void sdlog2_stop_log()
logwriter_pthread = 0;
pthread_attr_destroy(&logwriter_attr);
+ /* write all performance counters */
+ int perf_fd = open_perf_file("postflight");
+ dprintf(perf_fd, "PERFORMANCE COUNTERS POST-FLIGHT\n\n");
+ perf_print_all(perf_fd);
+ close(perf_fd);
+
sdlog2_status();
}
@@ -572,7 +671,7 @@ int write_formats(int fd)
int written = 0;
/* fill message format packet for each format and write it */
- for (int i = 0; i < log_formats_num; i++) {
+ for (unsigned i = 0; i < log_formats_num; i++) {
log_msg_format.body = log_formats[i];
written += write(fd, &log_msg_format, sizeof(log_msg_format));
}
@@ -679,12 +778,12 @@ int sdlog2_thread_main(int argc, char *argv[])
* set error flag instead */
bool err_flag = false;
- while ((ch = getopt(argc, argv, "r:b:eat")) != EOF) {
+ while ((ch = getopt(argc, argv, "r:b:eatx")) != EOF) {
switch (ch) {
case 'r': {
unsigned long r = strtoul(optarg, NULL, 10);
- if (r <= 0) {
+ if (r == 0) {
r = 1;
}
@@ -715,6 +814,10 @@ int sdlog2_thread_main(int argc, char *argv[])
log_name_timestamp = true;
break;
+ case 'x':
+ _extended_logging = true;
+ break;
+
case '?':
if (optopt == 'c') {
warnx("option -%c requires an argument", optopt);
@@ -741,6 +844,44 @@ int sdlog2_thread_main(int argc, char *argv[])
gps_time = 0;
+ /* interpret logging params */
+
+ param_t log_rate_ph = param_find("SDLOG_RATE");
+
+ if (log_rate_ph != PARAM_INVALID) {
+ int32_t param_log_rate;
+ param_get(log_rate_ph, &param_log_rate);
+
+ if (param_log_rate > 0) {
+
+ /* we can't do more than ~ 500 Hz, even with a massive buffer */
+ if (param_log_rate > 500) {
+ param_log_rate = 500;
+ }
+
+ sleep_delay = 1000000 / param_log_rate;
+ } else if (param_log_rate == 0) {
+ /* we need at minimum 10 Hz to be able to see anything */
+ sleep_delay = 1000000 / 10;
+ }
+ }
+
+ param_t log_ext_ph = param_find("SDLOG_EXT");
+
+ if (log_ext_ph != PARAM_INVALID) {
+
+ int32_t param_log_extended;
+ param_get(log_ext_ph, &param_log_extended);
+
+ if (param_log_extended > 0) {
+ _extended_logging = true;
+ } else if (param_log_extended == 0) {
+ _extended_logging = false;
+ }
+ /* any other value means to ignore the parameter, so no else case */
+
+ }
+
/* create log root dir */
int mkdir_ret = mkdir(log_root, S_IRWXU | S_IRWXG | S_IRWXO);
@@ -834,6 +975,10 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_ESTM_s log_ESTM;
struct log_PWR_s log_PWR;
struct log_VICN_s log_VICN;
+ struct log_GS0A_s log_GS0A;
+ struct log_GS0B_s log_GS0B;
+ struct log_GS1A_s log_GS1A;
+ struct log_GS1B_s log_GS1B;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -967,8 +1112,17 @@ int sdlog2_thread_main(int argc, char *argv[])
LOGBUFFER_WRITE_AND_COUNT(STAT);
}
- /* --- GPS POSITION --- */
+ /* --- GPS POSITION - UNIT #1 --- */
if (gps_pos_updated) {
+
+ float snr_mean = 0.0f;
+
+ for (unsigned i = 0; i < buf_gps_pos.satellites_visible; i++) {
+ snr_mean += buf_gps_pos.satellite_snr[i];
+ }
+
+ snr_mean /= buf_gps_pos.satellites_visible;
+
log_msg.msg_type = LOG_GPS_MSG;
log_msg.body.log_GPS.gps_time = buf_gps_pos.time_gps_usec;
log_msg.body.log_GPS.fix_type = buf_gps_pos.fix_type;
@@ -981,7 +1135,48 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_GPS.vel_e = buf_gps_pos.vel_e_m_s;
log_msg.body.log_GPS.vel_d = buf_gps_pos.vel_d_m_s;
log_msg.body.log_GPS.cog = buf_gps_pos.cog_rad;
+ log_msg.body.log_GPS.sats = buf_gps_pos.satellites_visible;
+ log_msg.body.log_GPS.snr_mean = snr_mean;
+ log_msg.body.log_GPS.noise_per_ms = buf_gps_pos.noise_per_ms;
+ log_msg.body.log_GPS.jamming_indicator = buf_gps_pos.jamming_indicator;
LOGBUFFER_WRITE_AND_COUNT(GPS);
+
+ if (_extended_logging) {
+ /* log the SNR of each satellite for a detailed view of signal quality */
+ unsigned gps_msg_max_snr = sizeof(buf_gps_pos.satellite_snr) / sizeof(buf_gps_pos.satellite_snr[0]);
+ unsigned log_max_snr = sizeof(log_msg.body.log_GS0A.satellite_snr) / sizeof(log_msg.body.log_GS0A.satellite_snr[0]);
+
+ log_msg.msg_type = LOG_GS0A_MSG;
+ memset(&log_msg.body.log_GS0A, 0, sizeof(log_msg.body.log_GS0A));
+ /* fill set A */
+ for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+
+ int satindex = buf_gps_pos.satellite_prn[i] - 1;
+
+ /* handles index exceeding and wraps to to arithmetic errors */
+ if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
+ /* map satellites by their ID so that logs from two receivers can be compared */
+ log_msg.body.log_GS0A.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ }
+ }
+ LOGBUFFER_WRITE_AND_COUNT(GS0A);
+
+ log_msg.msg_type = LOG_GS0B_MSG;
+ memset(&log_msg.body.log_GS0B, 0, sizeof(log_msg.body.log_GS0B));
+ /* fill set B */
+ for (unsigned i = 0; i < gps_msg_max_snr; i++) {
+
+ /* get second bank of satellites, thus deduct bank size from index */
+ int satindex = buf_gps_pos.satellite_prn[i] - 1 - log_max_snr;
+
+ /* handles index exceeding and wraps to to arithmetic errors */
+ if ((satindex >= 0) && (satindex < (int)log_max_snr)) {
+ /* map satellites by their ID so that logs from two receivers can be compared */
+ log_msg.body.log_GS0B.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i];
+ }
+ }
+ LOGBUFFER_WRITE_AND_COUNT(GS0B);
+ }
}
/* --- SENSOR COMBINED --- */
@@ -1105,10 +1300,16 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat * 1e7;
log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon * 1e7;
log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
- log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
- log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.pos_flags = (buf.local_pos.xy_valid ? 1 : 0) |
+ (buf.local_pos.z_valid ? 2 : 0) |
+ (buf.local_pos.v_xy_valid ? 4 : 0) |
+ (buf.local_pos.v_z_valid ? 8 : 0) |
+ (buf.local_pos.xy_global ? 16 : 0) |
+ (buf.local_pos.z_global ? 32 : 0);
log_msg.body.log_LPOS.landed = buf.local_pos.landed;
log_msg.body.log_LPOS.ground_dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
+ log_msg.body.log_LPOS.eph = buf.local_pos.eph;
+ log_msg.body.log_LPOS.epv = buf.local_pos.epv;
LOGBUFFER_WRITE_AND_COUNT(LPOS);
}
@@ -1320,6 +1521,7 @@ void sdlog2_status()
float seconds = ((float)(hrt_absolute_time() - start_time)) / 1000000.0f;
warnx("wrote %lu msgs, %4.2f MiB (average %5.3f KiB/s), skipped %lu msgs", log_msgs_written, (double)mebibytes, (double)(kibibytes / seconds), log_msgs_skipped);
+ warnx("extended logging: %s", (_extended_logging) ? "ON" : "OFF");
mavlink_log_info(mavlink_fd, "[sdlog2] wrote %lu msgs, skipped %lu msgs", log_msgs_written, log_msgs_skipped);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 595a787d6..f4d88f079 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -109,10 +109,11 @@ struct log_LPOS_s {
int32_t ref_lat;
int32_t ref_lon;
float ref_alt;
- uint8_t xy_flags;
- uint8_t z_flags;
+ uint8_t pos_flags;
uint8_t landed;
uint8_t ground_dist_flags;
+ float eph;
+ float epv;
};
/* --- LPSP - LOCAL POSITION SETPOINT --- */
@@ -138,6 +139,10 @@ struct log_GPS_s {
float vel_e;
float vel_d;
float cog;
+ uint8_t sats;
+ uint16_t snr_mean;
+ uint16_t noise_per_ms;
+ uint16_t jamming_indicator;
};
/* --- ATTC - ATTITUDE CONTROLS (ACTUATOR_0 CONTROLS)--- */
@@ -317,6 +322,30 @@ struct log_VICN_s {
float yaw;
};
+/* --- GS0A - GPS SNR #0, SAT GROUP A --- */
+#define LOG_GS0A_MSG 26
+struct log_GS0A_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS0B - GPS SNR #0, SAT GROUP B --- */
+#define LOG_GS0B_MSG 27
+struct log_GS0B_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS1A - GPS SNR #1, SAT GROUP A --- */
+#define LOG_GS1A_MSG 28
+struct log_GS1A_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
+/* --- GS1B - GPS SNR #1, SAT GROUP B --- */
+#define LOG_GS1B_MSG 29
+struct log_GS1B_s {
+ uint8_t satellite_snr[16]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99 */
+};
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -348,9 +377,9 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"),
- LOG_FORMAT(LPOS, "ffffffffLLfBBBB", "X,Y,Z,dist,distR,VX,VY,VZ,RLat,RLon,RAlt,XYFlg,ZFlg,LFlg,GFlg"),
+ LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
- LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
+ LOG_FORMAT(GPS, "QBffLLfffffBHHH", "GPSTime,Fix,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog,nSat,SNR,N,J"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
LOG_FORMAT(STAT, "BBBfBB", "MainState,ArmState,FailsafeState,BatRem,BatWarn,Landed"),
LOG_FORMAT(RC, "ffffffffBB", "Ch0,Ch1,Ch2,Ch3,Ch4,Ch5,Ch6,Ch7,Count,SignalLost"),
@@ -368,6 +397,10 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ESTM, "ffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,nStat,statNaN,covNaN,kGainNaN"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
LOG_FORMAT(VICN, "ffffff", "X,Y,Z,Roll,Pitch,Yaw"),
+ LOG_FORMAT(GS0A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
+ LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"),
/* system-level messages, ID >= 0x80 */
/* FMT: don't write format of format message, it's useless */
diff --git a/src/modules/segway/BlockSegwayController.cpp b/src/modules/segway/BlockSegwayController.cpp
index 96a443c6e..91230a37c 100644
--- a/src/modules/segway/BlockSegwayController.cpp
+++ b/src/modules/segway/BlockSegwayController.cpp
@@ -35,8 +35,8 @@ void BlockSegwayController::update() {
// handle autopilot modes
if (_status.main_state == MAIN_STATE_AUTO ||
- _status.main_state == MAIN_STATE_SEATBELT ||
- _status.main_state == MAIN_STATE_EASY) {
+ _status.main_state == MAIN_STATE_ALTCTL ||
+ _status.main_state == MAIN_STATE_POSCTL) {
_actuators.control[0] = spdCmd;
_actuators.control[1] = spdCmd;
diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk
index aa538fd6b..5b1bc5e86 100644
--- a/src/modules/sensors/module.mk
+++ b/src/modules/sensors/module.mk
@@ -40,3 +40,5 @@ MODULE_PRIORITY = "SCHED_PRIORITY_MAX-5"
SRCS = sensors.cpp \
sensor_params.c
+
+MODULE_STACKSIZE = 1200
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index bc49f5c85..999cf8bb3 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -488,6 +488,15 @@ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000);
* @group Battery Calibration
*/
PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f);
+#elif CONFIG_ARCH_BOARD_AEROCORE
+/**
+ * Scaling factor for battery voltage sensor on AeroCore.
+ *
+ * For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063
+ *
+ * @group Battery Calibration
+ */
+PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0063f);
#else
/**
* Scaling factor for battery voltage sensor on FMU v1.
@@ -536,6 +545,20 @@ PARAM_DEFINE_INT32(RC_MAP_ROLL, 1);
PARAM_DEFINE_INT32(RC_MAP_PITCH, 2);
/**
+ * Failsafe channel mapping.
+ *
+ * The RC mapping index indicates which channel is used for failsafe
+ * If 0, whichever channel is mapped to throttle is used
+ * otherwise the value indicates the specific rc channel to use
+ *
+ * @min 0
+ * @max 18
+ *
+ *
+ */
+PARAM_DEFINE_INT32(RC_MAP_FAILSAFE, 0); //Default to throttle function
+
+/**
* Throttle control channel mapping.
*
* The channel index (starting from 1 for channel 1) indicates
@@ -585,13 +608,13 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
/**
- * Assist switch channel mapping.
+ * Posctl switch channel mapping.
*
* @min 0
* @max 18
* @group Radio Calibration
*/
-PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_POSCTL_SW, 0);
/**
* Loiter switch channel mapping.
@@ -602,7 +625,14 @@ PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0);
*/
PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
-//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+/**
+ * Acro switch channel mapping.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
/**
* Flaps channel mapping.
@@ -655,3 +685,99 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_FAILS_THR, 0);
+
+/**
+ * Threshold for selecting assist mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_ASSIST_TH, 0.25f);
+
+/**
+ * Threshold for selecting auto mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_AUTO_TH, 0.75f);
+
+/**
+ * Threshold for selecting posctl mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_POSCTL_TH, 0.5f);
+
+/**
+ * Threshold for selecting return to launch mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_RETURN_TH, 0.5f);
+
+/**
+ * Threshold for selecting loiter mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
+
+/**
+ * Threshold for selecting acro mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index e260aae45..b268b1b36 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -126,6 +126,12 @@
#define ADC_AIRSPEED_VOLTAGE_CHANNEL 15
#endif
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+#define ADC_BATTERY_VOLTAGE_CHANNEL 10
+#define ADC_BATTERY_CURRENT_CHANNEL -1
+#define ADC_AIRSPEED_VOLTAGE_CHANNEL -1
+#endif
+
#define BATT_V_LOWPASS 0.001f
#define BATT_V_IGNORE_THRESHOLD 3.5f
@@ -175,7 +181,8 @@ private:
/**
* Get switch position for specified function.
*/
- switch_pos_t get_rc_switch_position(enum RC_CHANNELS_FUNCTION func);
+ switch_pos_t get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv);
+ switch_pos_t get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv);
/**
* Gather and publish RC input data.
@@ -219,8 +226,8 @@ private:
struct differential_pressure_s _diff_pres;
struct airspeed_s _airspeed;
- math::Matrix<3,3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
- math::Matrix<3,3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
+ math::Matrix<3, 3> _board_rotation; /**< rotation matrix for the orientation that the board is mounted */
+ math::Matrix<3, 3> _external_mag_rotation; /**< rotation matrix for the orientation that an external mag is mounted */
bool _mag_is_external; /**< true if the active mag is on an external board */
uint64_t _battery_discharged; /**< battery discharged current in mA*ms */
@@ -250,13 +257,13 @@ private:
int rc_map_pitch;
int rc_map_yaw;
int rc_map_throttle;
+ int rc_map_failsafe;
int rc_map_mode_sw;
int rc_map_return_sw;
- int rc_map_assisted_sw;
+ int rc_map_posctl_sw;
int rc_map_loiter_sw;
-
-// int rc_map_offboard_ctrl_mode_sw;
+ int rc_map_acro_sw;
int rc_map_flaps;
@@ -266,7 +273,19 @@ private:
int rc_map_aux4;
int rc_map_aux5;
- int32_t rc_fs_thr;
+ int32_t rc_fails_thr;
+ float rc_assist_th;
+ float rc_auto_th;
+ float rc_posctl_th;
+ float rc_return_th;
+ float rc_loiter_th;
+ float rc_acro_th;
+ bool rc_assist_inv;
+ bool rc_auto_inv;
+ bool rc_posctl_inv;
+ bool rc_return_inv;
+ bool rc_loiter_inv;
+ bool rc_acro_inv;
float battery_voltage_scaling;
float battery_current_scaling;
@@ -293,13 +312,13 @@ private:
param_t rc_map_pitch;
param_t rc_map_yaw;
param_t rc_map_throttle;
+ param_t rc_map_failsafe;
param_t rc_map_mode_sw;
param_t rc_map_return_sw;
- param_t rc_map_assisted_sw;
+ param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
-
-// param_t rc_map_offboard_ctrl_mode_sw;
+ param_t rc_map_acro_sw;
param_t rc_map_flaps;
@@ -309,7 +328,13 @@ private:
param_t rc_map_aux4;
param_t rc_map_aux5;
- param_t rc_fs_thr;
+ param_t rc_fails_thr;
+ param_t rc_assist_th;
+ param_t rc_auto_th;
+ param_t rc_posctl_th;
+ param_t rc_return_th;
+ param_t rc_loiter_th;
+ param_t rc_acro_th;
param_t battery_voltage_scaling;
param_t battery_current_scaling;
@@ -416,7 +441,7 @@ private:
/**
* Main sensor collection task.
*/
- void task_main() __attribute__((noreturn));
+ void task_main();
};
namespace sensors
@@ -499,6 +524,7 @@ Sensors::Sensors() :
_parameter_handles.rc_map_pitch = param_find("RC_MAP_PITCH");
_parameter_handles.rc_map_yaw = param_find("RC_MAP_YAW");
_parameter_handles.rc_map_throttle = param_find("RC_MAP_THROTTLE");
+ _parameter_handles.rc_map_failsafe = param_find("RC_MAP_FAILSAFE");
/* mandatory mode switches, mapped to channel 5 and 6 per default */
_parameter_handles.rc_map_mode_sw = param_find("RC_MAP_MODE_SW");
@@ -507,10 +533,9 @@ Sensors::Sensors() :
_parameter_handles.rc_map_flaps = param_find("RC_MAP_FLAPS");
/* optional mode switches, not mapped per default */
- _parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
+ _parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
-
-// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
+ _parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -518,8 +543,14 @@ Sensors::Sensors() :
_parameter_handles.rc_map_aux4 = param_find("RC_MAP_AUX4");
_parameter_handles.rc_map_aux5 = param_find("RC_MAP_AUX5");
- /* RC failsafe */
- _parameter_handles.rc_fs_thr = param_find("RC_FAILS_THR");
+ /* RC thresholds */
+ _parameter_handles.rc_fails_thr = param_find("RC_FAILS_THR");
+ _parameter_handles.rc_assist_th = param_find("RC_ASSIST_TH");
+ _parameter_handles.rc_auto_th = param_find("RC_AUTO_TH");
+ _parameter_handles.rc_posctl_th = param_find("RC_POSCTL_TH");
+ _parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
+ _parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
+ _parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
@@ -620,8 +651,9 @@ Sensors::parameters_update()
}
/* handle wrong values */
- if (!rc_valid)
+ if (!rc_valid) {
warnx("WARNING WARNING WARNING\n\nRC CALIBRATION NOT SANE!\n\n");
+ }
const char *paramerr = "FAIL PARM LOAD";
@@ -642,6 +674,10 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
+ if (param_get(_parameter_handles.rc_map_failsafe, &(_parameters.rc_map_failsafe)) != OK) {
+ warnx("%s", paramerr);
+ }
+
if (param_get(_parameter_handles.rc_map_mode_sw, &(_parameters.rc_map_mode_sw)) != OK) {
warnx("%s", paramerr);
}
@@ -650,7 +686,7 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_assisted_sw, &(_parameters.rc_map_assisted_sw)) != OK) {
+ if (param_get(_parameter_handles.rc_map_posctl_sw, &(_parameters.rc_map_posctl_sw)) != OK) {
warnx("%s", paramerr);
}
@@ -658,20 +694,38 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
- if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ if (param_get(_parameter_handles.rc_map_acro_sw, &(_parameters.rc_map_acro_sw)) != OK) {
warnx("%s", paramerr);
}
-// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) {
-// warnx("Failed getting offboard control mode sw chan index");
-// }
+ if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
+ warnx("%s", paramerr);
+ }
param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1));
param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2));
param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3));
param_get(_parameter_handles.rc_map_aux4, &(_parameters.rc_map_aux4));
param_get(_parameter_handles.rc_map_aux5, &(_parameters.rc_map_aux5));
- param_get(_parameter_handles.rc_fs_thr, &(_parameters.rc_fs_thr));
+ param_get(_parameter_handles.rc_fails_thr, &(_parameters.rc_fails_thr));
+ param_get(_parameter_handles.rc_assist_th, &(_parameters.rc_assist_th));
+ _parameters.rc_assist_inv = (_parameters.rc_assist_th < 0);
+ _parameters.rc_assist_th = fabs(_parameters.rc_assist_th);
+ param_get(_parameter_handles.rc_auto_th, &(_parameters.rc_auto_th));
+ _parameters.rc_auto_inv = (_parameters.rc_auto_th < 0);
+ _parameters.rc_auto_th = fabs(_parameters.rc_auto_th);
+ param_get(_parameter_handles.rc_posctl_th, &(_parameters.rc_posctl_th));
+ _parameters.rc_posctl_inv = (_parameters.rc_posctl_th < 0);
+ _parameters.rc_posctl_th = fabs(_parameters.rc_posctl_th);
+ param_get(_parameter_handles.rc_return_th, &(_parameters.rc_return_th));
+ _parameters.rc_return_inv = (_parameters.rc_return_th < 0);
+ _parameters.rc_return_th = fabs(_parameters.rc_return_th);
+ param_get(_parameter_handles.rc_loiter_th, &(_parameters.rc_loiter_th));
+ _parameters.rc_loiter_inv = (_parameters.rc_loiter_th < 0);
+ _parameters.rc_loiter_th = fabs(_parameters.rc_loiter_th);
+ param_get(_parameter_handles.rc_acro_th, &(_parameters.rc_acro_th));
+ _parameters.rc_acro_inv = (_parameters.rc_acro_th < 0);
+ _parameters.rc_acro_th = fabs(_parameters.rc_acro_th);
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -681,13 +735,12 @@ Sensors::parameters_update()
_rc.function[MODE] = _parameters.rc_map_mode_sw - 1;
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
- _rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
+ _rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
+ _rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
-// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1;
-
_rc.function[AUX_1] = _parameters.rc_map_aux1 - 1;
_rc.function[AUX_2] = _parameters.rc_map_aux2 - 1;
_rc.function[AUX_3] = _parameters.rc_map_aux3 - 1;
@@ -765,7 +818,7 @@ Sensors::accel_init()
/* set the driver to poll at 1000Hz */
ioctl(fd, SENSORIOCSPOLLRATE, 1000);
-#elif CONFIG_ARCH_BOARD_PX4FMU_V2
+#elif CONFIG_ARCH_BOARD_PX4FMU_V2 || CONFIG_ARCH_BOARD_AEROCORE
/* set the accel internal sampling rate up to at leat 800Hz */
ioctl(fd, ACCELIOCSSAMPLERATE, 800);
@@ -774,7 +827,7 @@ Sensors::accel_init()
ioctl(fd, SENSORIOCSPOLLRATE, 800);
#else
-#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1 or CONFIG_ARCH_BOARD_PX4FMU_V2
+#error Need a board configuration, either CONFIG_ARCH_BOARD_PX4FMU_V1, CONFIG_ARCH_BOARD_PX4FMU_V2 or CONFIG_ARCH_BOARD_AEROCORE
#endif
@@ -800,12 +853,14 @@ Sensors::gyro_init()
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
/* set the gyro internal sampling rate up to at least 1000Hz */
- if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK)
+ if (ioctl(fd, GYROIOCSSAMPLERATE, 1000) != OK) {
ioctl(fd, GYROIOCSSAMPLERATE, 800);
+ }
/* set the driver to poll at 1000Hz */
- if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK)
+ if (ioctl(fd, SENSORIOCSPOLLRATE, 1000) != OK) {
ioctl(fd, SENSORIOCSPOLLRATE, 800);
+ }
#else
@@ -860,12 +915,15 @@ Sensors::mag_init()
ret = ioctl(fd, MAGIOCGEXTERNAL, 0);
- if (ret < 0)
+ if (ret < 0) {
errx(1, "FATAL: unknown if magnetometer is external or onboard");
- else if (ret == 1)
+
+ } else if (ret == 1) {
_mag_is_external = true;
- else
+
+ } else {
_mag_is_external = false;
+ }
close(fd);
}
@@ -965,10 +1023,12 @@ Sensors::mag_poll(struct sensor_combined_s &raw)
math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z);
- if (_mag_is_external)
+ if (_mag_is_external) {
vect = _external_mag_rotation * vect;
- else
+
+ } else {
vect = _board_rotation * vect;
+ }
raw.magnetometer_ga[0] = vect(0);
raw.magnetometer_ga[1] = vect(1);
@@ -1086,8 +1146,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.gyro_scale[2],
};
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale)) {
warn("WARNING: failed to set scale / offsets for gyro");
+ }
close(fd);
@@ -1101,8 +1162,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.accel_scale[2],
};
- if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale))
+ if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) {
warn("WARNING: failed to set scale / offsets for accel");
+ }
close(fd);
@@ -1116,8 +1178,9 @@ Sensors::parameter_update_poll(bool forced)
_parameters.mag_scale[2],
};
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
+ if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale)) {
warn("WARNING: failed to set scale / offsets for mag");
+ }
close(fd);
@@ -1131,8 +1194,10 @@ Sensors::parameter_update_poll(bool forced)
1.0f,
};
- if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale))
+ if (OK != ioctl(fd, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) {
warn("WARNING: failed to set scale / offsets for airspeed sensor");
+ }
+
close(fd);
}
@@ -1150,10 +1215,12 @@ void
Sensors::adc_poll(struct sensor_combined_s &raw)
{
/* only read if publishing */
- if (!_publishing)
+ if (!_publishing) {
return;
+ }
hrt_abstime t = hrt_absolute_time();
+
/* rate limit to 100 Hz */
if (t - _last_adc >= 10000) {
/* make space for a maximum of twelve channels (to ensure reading all channels at once) */
@@ -1178,6 +1245,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
if (voltage > BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_v = voltage;
+
/* one-time initialization of low-pass value to avoid long init delays */
if (_battery_status.voltage_filtered_v < BATT_V_IGNORE_THRESHOLD) {
_battery_status.voltage_filtered_v = voltage;
@@ -1196,19 +1264,24 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
/* handle current only if voltage is valid */
if (_battery_status.voltage_v > 0.0f) {
float current = (buf_adc[i].am_data * _parameters.battery_current_scaling);
+
/* check measured current value */
if (current >= 0.0f) {
_battery_status.timestamp = t;
_battery_status.current_a = current;
+
if (_battery_current_timestamp != 0) {
/* initialize discharged value */
- if (_battery_status.discharged_mah < 0.0f)
+ if (_battery_status.discharged_mah < 0.0f) {
_battery_status.discharged_mah = 0.0f;
+ }
+
_battery_discharged += current * (t - _battery_current_timestamp);
_battery_status.discharged_mah = ((float) _battery_discharged) / 3600000.0f;
}
}
}
+
_battery_current_timestamp = t;
} else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) {
@@ -1241,7 +1314,9 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
}
}
}
+
_last_adc = t;
+
if (_battery_status.voltage_filtered_v > BATT_V_IGNORE_THRESHOLD) {
/* announce the battery status if needed, just publish else */
if (_battery_pub > 0) {
@@ -1260,6 +1335,7 @@ Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max
{
if (_rc.function[func] >= 0) {
float value = _rc.chan[_rc.function[func]].scaled;
+
if (value < min_value) {
return min_value;
@@ -1269,24 +1345,44 @@ Sensors::get_rc_value(enum RC_CHANNELS_FUNCTION func, float min_value, float max
} else {
return value;
}
+
} else {
return 0.0f;
}
}
switch_pos_t
-Sensors::get_rc_switch_position(enum RC_CHANNELS_FUNCTION func)
+Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv, float mid_th, bool mid_inv)
{
if (_rc.function[func] >= 0) {
- float value = _rc.chan[_rc.function[func]].scaled;
- if (value > STICK_ON_OFF_LIMIT) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
- } else if (value < -STICK_ON_OFF_LIMIT) {
+ } else if (mid_inv ? value < mid_th : value > mid_th) {
+ return SWITCH_POS_MIDDLE;
+
+ } else {
return SWITCH_POS_OFF;
+ }
+
+ } else {
+ return SWITCH_POS_NONE;
+ }
+}
+
+switch_pos_t
+Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
+{
+ if (_rc.function[func] >= 0) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+
+ if (on_inv ? value < on_th : value > on_th) {
+ return SWITCH_POS_ON;
} else {
- return SWITCH_POS_MIDDLE;
+ return SWITCH_POS_OFF;
}
} else {
@@ -1318,13 +1414,18 @@ Sensors::rc_poll()
/* signal looks good */
signal_lost = false;
- /* check throttle failsafe */
- int8_t thr_ch = _rc.function[THROTTLE];
- if (_parameters.rc_fs_thr > 0 && thr_ch >= 0) {
- /* throttle failsafe configured */
- if ((_parameters.rc_fs_thr < _parameters.min[thr_ch] && rc_input.values[thr_ch] < _parameters.rc_fs_thr) ||
- (_parameters.rc_fs_thr > _parameters.max[thr_ch] && rc_input.values[thr_ch] > _parameters.rc_fs_thr)) {
- /* throttle failsafe triggered, signal is lost by receiver */
+ /* check failsafe */
+ int8_t fs_ch = _rc.function[_parameters.rc_map_failsafe]; // get channel mapped to throttle
+
+ if (_parameters.rc_map_failsafe > 0) { // if not 0, use channel number instead of rc.function mapping
+ fs_ch = _parameters.rc_map_failsafe - 1;
+ }
+
+ if (_parameters.rc_fails_thr > 0 && fs_ch >= 0) {
+ /* failsafe configured */
+ if ((_parameters.rc_fails_thr < _parameters.min[fs_ch] && rc_input.values[fs_ch] < _parameters.rc_fails_thr) ||
+ (_parameters.rc_fails_thr > _parameters.max[fs_ch] && rc_input.values[fs_ch] > _parameters.rc_fails_thr)) {
+ /* failsafe triggered, signal is lost by receiver */
signal_lost = true;
}
}
@@ -1332,8 +1433,9 @@ Sensors::rc_poll()
unsigned channel_limit = rc_input.channel_count;
- if (channel_limit > _rc_max_chan_count)
+ if (channel_limit > _rc_max_chan_count) {
channel_limit = _rc_max_chan_count;
+ }
/* read out and scale values from raw message even if signal is invalid */
for (unsigned int i = 0; i < channel_limit; i++) {
@@ -1341,11 +1443,13 @@ Sensors::rc_poll()
/*
* 1) Constrain to min/max values, as later processing depends on bounds.
*/
- if (rc_input.values[i] < _parameters.min[i])
+ if (rc_input.values[i] < _parameters.min[i]) {
rc_input.values[i] = _parameters.min[i];
+ }
- if (rc_input.values[i] > _parameters.max[i])
+ if (rc_input.values[i] > _parameters.max[i]) {
rc_input.values[i] = _parameters.max[i];
+ }
/*
* 2) Scale around the mid point differently for lower and upper range.
@@ -1377,8 +1481,9 @@ Sensors::rc_poll()
_rc.chan[i].scaled *= _parameters.rev[i];
/* handle any parameter-induced blowups */
- if (!isfinite(_rc.chan[i].scaled))
+ if (!isfinite(_rc.chan[i].scaled)) {
_rc.chan[i].scaled = 0.0f;
+ }
}
_rc.chan_count = rc_input.channel_count;
@@ -1402,10 +1507,10 @@ Sensors::rc_poll()
manual.timestamp = rc_input.timestamp_last_signal;
/* limit controls */
- manual.roll = get_rc_value(ROLL, -1.0, 1.0);
- manual.pitch = get_rc_value(PITCH, -1.0, 1.0);
- manual.yaw = get_rc_value(YAW, -1.0, 1.0);
- manual.throttle = get_rc_value(THROTTLE, 0.0, 1.0);
+ manual.y = get_rc_value(ROLL, -1.0, 1.0);
+ manual.x = get_rc_value(PITCH, -1.0, 1.0);
+ manual.r = get_rc_value(YAW, -1.0, 1.0);
+ manual.z = get_rc_value(THROTTLE, 0.0, 1.0);
manual.flaps = get_rc_value(FLAPS, -1.0, 1.0);
manual.aux1 = get_rc_value(AUX_1, -1.0, 1.0);
manual.aux2 = get_rc_value(AUX_2, -1.0, 1.0);
@@ -1414,10 +1519,11 @@ Sensors::rc_poll()
manual.aux5 = get_rc_value(AUX_5, -1.0, 1.0);
/* mode switches */
- manual.mode_switch = get_rc_switch_position(MODE);
- manual.assisted_switch = get_rc_switch_position(ASSISTED);
- manual.loiter_switch = get_rc_switch_position(LOITER);
- manual.return_switch = get_rc_switch_position(RETURN);
+ manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assist_th, _parameters.rc_assist_inv);
+ manual.posctl_switch = get_rc_sw2pos_position(POSCTL, _parameters.rc_posctl_th, _parameters.rc_posctl_inv);
+ manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
+ manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
+ manual.acro_switch = get_rc_sw2pos_position(ACRO, _parameters.rc_acro_th, _parameters.rc_acro_inv);
/* publish manual_control_setpoint topic */
if (_manual_control_pub > 0) {
@@ -1433,10 +1539,10 @@ Sensors::rc_poll()
actuator_group_3.timestamp = rc_input.timestamp_last_signal;
- actuator_group_3.control[0] = manual.roll;
- actuator_group_3.control[1] = manual.pitch;
- actuator_group_3.control[2] = manual.yaw;
- actuator_group_3.control[3] = manual.throttle;
+ actuator_group_3.control[0] = manual.y;
+ actuator_group_3.control[1] = manual.x;
+ actuator_group_3.control[2] = manual.r;
+ actuator_group_3.control[3] = manual.z;
actuator_group_3.control[4] = manual.flaps;
actuator_group_3.control[5] = manual.aux1;
actuator_group_3.control[6] = manual.aux2;
@@ -1560,8 +1666,9 @@ Sensors::task_main()
diff_pres_poll(raw);
/* Inform other processes that new data is available to copy */
- if (_publishing)
+ if (_publishing) {
orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw);
+ }
/* Look for new r/c input data */
rc_poll();
@@ -1584,7 +1691,7 @@ Sensors::start()
_sensors_task = task_spawn_cmd("sensors_task",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 2048,
+ 2000,
(main_t)&Sensors::task_main_trampoline,
nullptr);
@@ -1598,18 +1705,21 @@ Sensors::start()
int sensors_main(int argc, char *argv[])
{
- if (argc < 1)
+ if (argc < 1) {
errx(1, "usage: sensors {start|stop|status}");
+ }
if (!strcmp(argv[1], "start")) {
- if (sensors::g_sensors != nullptr)
+ if (sensors::g_sensors != nullptr) {
errx(0, "already running");
+ }
sensors::g_sensors = new Sensors;
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "alloc failed");
+ }
if (OK != sensors::g_sensors->start()) {
delete sensors::g_sensors;
@@ -1621,8 +1731,9 @@ int sensors_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- if (sensors::g_sensors == nullptr)
+ if (sensors::g_sensors == nullptr) {
errx(1, "not running");
+ }
delete sensors::g_sensors;
sensors::g_sensors = nullptr;
@@ -1641,4 +1752,3 @@ int sensors_main(int argc, char *argv[])
warnx("unrecognized command");
return 1;
}
-
diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h
index 1c889a811..225570fa4 100644
--- a/src/modules/systemlib/mixer/mixer.h
+++ b/src/modules/systemlib/mixer/mixer.h
@@ -447,6 +447,7 @@ public:
QUAD_WIDE, /**< quad in wide configuration */
HEX_X, /**< hex in X configuration */
HEX_PLUS, /**< hex in + configuration */
+ HEX_COX,
OCTA_X,
OCTA_PLUS,
OCTA_COX,
@@ -516,7 +517,7 @@ private:
float _roll_scale;
float _pitch_scale;
float _yaw_scale;
- float _deadband;
+ float _idle_speed;
unsigned _rotor_count;
const Rotor *_rotors;
diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c
index b05273c0d..bf3428a50 100644
--- a/src/modules/systemlib/mixer/mixer_load.c
+++ b/src/modules/systemlib/mixer/mixer_load.c
@@ -41,6 +41,7 @@
#include <string.h>
#include <stdio.h>
#include <ctype.h>
+#include <systemlib/err.h>
#include "mixer_load.h"
diff --git a/src/modules/systemlib/mixer/mixer_multirotor.cpp b/src/modules/systemlib/mixer/mixer_multirotor.cpp
index bf77795d5..092c0e2b0 100644
--- a/src/modules/systemlib/mixer/mixer_multirotor.cpp
+++ b/src/modules/systemlib/mixer/mixer_multirotor.cpp
@@ -67,6 +67,11 @@
namespace
{
+float constrain(float val, float min, float max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
/*
* These tables automatically generated by multi_tables - do not edit.
*/
@@ -110,6 +115,14 @@ const MultirotorMixer::Rotor _config_hex_plus[] = {
{ 0.866025, 0.500000, 1.00 },
{ -0.866025, -0.500000, -1.00 },
};
+const MultirotorMixer::Rotor _config_hex_cox[] = {
+ { -0.866025, 0.500000, -1.00 },
+ { -0.866025, 0.500000, 1.00 },
+ { -0.000000, -1.000000, -1.00 },
+ { -0.000000, -1.000000, 1.00 },
+ { 0.866025, 0.500000, -1.00 },
+ { 0.866025, 0.500000, 1.00 },
+};
const MultirotorMixer::Rotor _config_octa_x[] = {
{ -0.382683, 0.923880, -1.00 },
{ 0.382683, -0.923880, -1.00 },
@@ -147,6 +160,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::MAX_GEOMETRY] = {
&_config_quad_wide[0],
&_config_hex_x[0],
&_config_hex_plus[0],
+ &_config_hex_cox[0],
&_config_octa_x[0],
&_config_octa_plus[0],
&_config_octa_cox[0],
@@ -158,6 +172,7 @@ const unsigned _config_rotor_count[MultirotorMixer::MAX_GEOMETRY] = {
4, /* quad_wide */
6, /* hex_x */
6, /* hex_plus */
+ 6, /* hex_cox */
8, /* octa_x */
8, /* octa_plus */
8, /* octa_cox */
@@ -171,12 +186,12 @@ MultirotorMixer::MultirotorMixer(ControlCallback control_cb,
float roll_scale,
float pitch_scale,
float yaw_scale,
- float deadband) :
+ float idle_speed) :
Mixer(control_cb, cb_handle),
_roll_scale(roll_scale),
_pitch_scale(pitch_scale),
_yaw_scale(yaw_scale),
- _deadband(-1.0f + deadband), /* shift to output range here to avoid runtime calculation */
+ _idle_speed(-1.0f + idle_speed * 2.0f), /* shift to output range here to avoid runtime calculation */
_rotor_count(_config_rotor_count[geometry]),
_rotors(_config_index[geometry])
{
@@ -247,6 +262,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
} else if (!strcmp(geomname, "6x")) {
geometry = MultirotorMixer::HEX_X;
+ } else if (!strcmp(geomname, "6c")) {
+ geometry = MultirotorMixer::HEX_COX;
+
} else if (!strcmp(geomname, "8+")) {
geometry = MultirotorMixer::OCTA_PLUS;
@@ -276,67 +294,67 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
unsigned
MultirotorMixer::mix(float *outputs, unsigned space)
{
- float roll = get_control(0, 0) * _roll_scale;
+ float roll = constrain(get_control(0, 0) * _roll_scale, -1.0f, 1.0f);
//lowsyslog("roll: %d, get_control0: %d, %d\n", (int)(roll), (int)(get_control(0, 0)), (int)(_roll_scale));
- float pitch = get_control(0, 1) * _pitch_scale;
- float yaw = get_control(0, 2) * _yaw_scale;
- float thrust = get_control(0, 3);
+ float pitch = constrain(get_control(0, 1) * _pitch_scale, -1.0f, 1.0f);
+ float yaw = constrain(get_control(0, 2) * _yaw_scale, -1.0f, 1.0f);
+ float thrust = constrain(get_control(0, 3), 0.0f, 1.0f);
//lowsyslog("thrust: %d, get_control3: %d\n", (int)(thrust), (int)(get_control(0, 3)));
- float max = 0.0f;
- float fixup_scale;
+ float min_out = 0.0f;
+ float max_out = 0.0f;
+ float scale_yaw = 1.0f;
- /* use an output factor to prevent too strong control signals at low throttle */
- float min_thrust = 0.05f;
- float max_thrust = 1.0f;
- float startpoint_full_control = 0.40f;
- float output_factor;
+ /* perform initial mix pass yielding unbounded outputs, ignore yaw */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ float out = roll * _rotors[i].roll_scale +
+ pitch * _rotors[i].pitch_scale +
+ thrust;
- /* keep roll, pitch and yaw control to 0 below min thrust */
- if (thrust <= min_thrust) {
- output_factor = 0.0f;
- /* linearly increase the output factor from 0 to 1 between min_thrust and startpoint_full_control */
+ /* limit yaw if it causes outputs clipping */
+ if (out >= 0.0f && out < -yaw * _rotors[i].yaw_scale) {
+ yaw = -out / _rotors[i].yaw_scale;
+ }
- } else if (thrust < startpoint_full_control && thrust > min_thrust) {
- output_factor = (thrust / max_thrust) / (startpoint_full_control - min_thrust);
- /* and then stay at full control */
+ /* calculate min and max output values */
+ if (out < min_out) {
+ min_out = out;
+ }
+ if (out > max_out) {
+ max_out = out;
+ }
- } else {
- output_factor = max_thrust;
+ outputs[i] = out;
}
- roll *= output_factor;
- pitch *= output_factor;
- yaw *= output_factor;
-
-
- /* perform initial mix pass yielding un-bounded outputs */
- for (unsigned i = 0; i < _rotor_count; i++) {
- float tmp = roll * _rotors[i].roll_scale +
- pitch * _rotors[i].pitch_scale +
- yaw * _rotors[i].yaw_scale +
- thrust;
+ /* scale down roll/pitch controls if some outputs are negative, don't add yaw, keep total thrust */
+ if (min_out < 0.0) {
+ float scale_in = thrust / (thrust - min_out);
- if (tmp > max)
- max = tmp;
+ /* mix again with adjusted controls */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] = scale_in * (roll * _rotors[i].roll_scale + pitch * _rotors[i].pitch_scale) + thrust;
+ }
- outputs[i] = tmp;
+ } else {
+ /* roll/pitch mixed without limiting, add yaw control */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] += yaw * _rotors[i].yaw_scale;
+ }
}
- /* scale values into the -1.0 - 1.0 range */
- if (max > 1.0f) {
- fixup_scale = 2.0f / max;
+ /* scale down all outputs if some outputs are too large, reduce total thrust */
+ float scale_out;
+ if (max_out > 1.0f) {
+ scale_out = 1.0f / max_out;
} else {
- fixup_scale = 2.0f;
+ scale_out = 1.0f;
}
- for (unsigned i = 0; i < _rotor_count; i++)
- outputs[i] = -1.0f + (outputs[i] * fixup_scale);
-
- /* ensure outputs are out of the deadband */
- for (unsigned i = 0; i < _rotor_count; i++)
- if (outputs[i] < _deadband)
- outputs[i] = _deadband;
+ /* scale outputs to range _idle_speed..1, and do final limiting */
+ for (unsigned i = 0; i < _rotor_count; i++) {
+ outputs[i] = constrain(_idle_speed + (outputs[i] * (1.0f - _idle_speed) * scale_out), _idle_speed, 1.0f);
+ }
return _rotor_count;
}
diff --git a/src/modules/systemlib/mixer/multi_tables b/src/modules/systemlib/mixer/multi_tables
index 050bf2f47..b5698036e 100755
--- a/src/modules/systemlib/mixer/multi_tables
+++ b/src/modules/systemlib/mixer/multi_tables
@@ -52,6 +52,15 @@ set hex_plus {
120 CW
}
+set hex_cox {
+ 60 CW
+ 60 CCW
+ 180 CW
+ 180 CCW
+ -60 CW
+ -60 CCW
+}
+
set octa_x {
22.5 CW
-157.5 CW
@@ -85,7 +94,7 @@ set octa_cox {
-135 CW
}
-set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus octa_cox}
+set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus hex_cox octa_x octa_plus octa_cox}
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
@@ -104,13 +113,13 @@ foreach table $tables {
puts "};"
}
-puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
+puts "const MultirotorMixer::Rotor *_config_index\[MultirotorMixer::MAX_GEOMETRY\] = {"
foreach table $tables {
puts [format "\t&_config_%s\[0\]," $table]
}
puts "};"
-puts "const unsigned _config_rotor_count\[MultirotorMixer::Geometry::MAX_GEOMETRY\] = {"
+puts "const unsigned _config_rotor_count\[MultirotorMixer::MAX_GEOMETRY\] = {"
foreach table $tables {
upvar #0 $table angles
puts [format "\t%u, /* %s */" [expr [llength $angles] / 2] $table]
diff --git a/src/modules/systemlib/param/param.c b/src/modules/systemlib/param/param.c
index 2d773fd25..7a499ca72 100644
--- a/src/modules/systemlib/param/param.c
+++ b/src/modules/systemlib/param/param.c
@@ -521,73 +521,15 @@ param_save_default(void)
return ERROR;
}
- if (res == OK) {
- res = param_export(fd, false);
+ res = param_export(fd, false);
- if (res != OK) {
- warnx("failed to write parameters to file: %s", filename);
- }
+ if (res != OK) {
+ warnx("failed to write parameters to file: %s", filename);
}
close(fd);
return res;
-
-#if 0
- const char *filename_tmp = malloc(strlen(filename) + 5);
- sprintf(filename_tmp, "%s.tmp", filename);
-
- /* delete temp file if exist */
- res = unlink(filename_tmp);
-
- if (res != OK && errno == ENOENT)
- res = OK;
-
- if (res != OK)
- warn("failed to delete temp file: %s", filename_tmp);
-
- if (res == OK) {
- /* write parameters to temp file */
- fd = open(filename_tmp, O_WRONLY | O_CREAT | O_EXCL);
-
- if (fd < 0) {
- warn("failed to open temp file: %s", filename_tmp);
- res = ERROR;
- }
-
- if (res == OK) {
- res = param_export(fd, false);
-
- if (res != OK)
- warnx("failed to write parameters to file: %s", filename_tmp);
- }
-
- close(fd);
- }
-
- if (res == OK) {
- /* delete parameters file */
- res = unlink(filename);
-
- if (res != OK && errno == ENOENT)
- res = OK;
-
- if (res != OK)
- warn("failed to delete parameters file: %s", filename);
- }
-
- if (res == OK) {
- /* rename temp file to parameters */
- res = rename(filename_tmp, filename);
-
- if (res != OK)
- warn("failed to rename %s to %s", filename_tmp, filename);
- }
-
- free(filename_tmp);
-
- return res;
-#endif
}
/**
diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c
index b4ca0ed3e..22182e39e 100644
--- a/src/modules/systemlib/perf_counter.c
+++ b/src/modules/systemlib/perf_counter.c
@@ -282,12 +282,18 @@ perf_reset(perf_counter_t handle)
void
perf_print_counter(perf_counter_t handle)
{
+ perf_print_counter_fd(0, handle);
+}
+
+void
+perf_print_counter_fd(int fd, perf_counter_t handle)
+{
if (handle == NULL)
return;
switch (handle->type) {
case PC_COUNT:
- printf("%s: %llu events\n",
+ dprintf(fd, "%s: %llu events\n",
handle->name,
((struct perf_ctr_count *)handle)->event_count);
break;
@@ -295,7 +301,7 @@ perf_print_counter(perf_counter_t handle)
case PC_ELAPSED: {
struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle;
- printf("%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n",
handle->name,
pce->event_count,
pce->time_total,
@@ -308,7 +314,7 @@ perf_print_counter(perf_counter_t handle)
case PC_INTERVAL: {
struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle;
- printf("%s: %llu events, %llu avg, min %lluus max %lluus\n",
+ dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n",
handle->name,
pci->event_count,
(pci->time_last - pci->time_first) / pci->event_count,
@@ -349,12 +355,12 @@ perf_event_count(perf_counter_t handle)
}
void
-perf_print_all(void)
+perf_print_all(int fd)
{
perf_counter_t handle = (perf_counter_t)sq_peek(&perf_counters);
while (handle != NULL) {
- perf_print_counter(handle);
+ perf_print_counter_fd(fd, handle);
handle = (perf_counter_t)sq_next(&handle->link);
}
}
diff --git a/src/modules/systemlib/perf_counter.h b/src/modules/systemlib/perf_counter.h
index d8f69fdbf..6835ee4a2 100644
--- a/src/modules/systemlib/perf_counter.h
+++ b/src/modules/systemlib/perf_counter.h
@@ -121,16 +121,26 @@ __EXPORT extern void perf_cancel(perf_counter_t handle);
__EXPORT extern void perf_reset(perf_counter_t handle);
/**
- * Print one performance counter.
+ * Print one performance counter to stdout
*
* @param handle The counter to print.
*/
__EXPORT extern void perf_print_counter(perf_counter_t handle);
/**
+ * Print one performance counter to a fd.
+ *
+ * @param fd File descriptor to print to - e.g. 0 for stdout
+ * @param handle The counter to print.
+ */
+__EXPORT extern void perf_print_counter_fd(int fd, perf_counter_t handle);
+
+/**
* Print all of the performance counters.
+ *
+ * @param fd File descriptor to print to - e.g. 0 for stdout
*/
-__EXPORT extern void perf_print_all(void);
+__EXPORT extern void perf_print_all(int fd);
/**
* Reset all of the performance counters.
diff --git a/src/modules/systemlib/pid/pid.c b/src/modules/systemlib/pid/pid.c
index 6a4e9392a..45f218a5b 100644
--- a/src/modules/systemlib/pid/pid.c
+++ b/src/modules/systemlib/pid/pid.c
@@ -53,7 +53,7 @@
#define SIGMA 0.000001f
-__EXPORT void pid_init(PID_t *pid, uint8_t mode, float dt_min)
+__EXPORT void pid_init(PID_t *pid, pid_mode_t mode, float dt_min)
{
pid->mode = mode;
pid->dt_min = dt_min;
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.c b/src/modules/systemlib/pwm_limit/pwm_limit.c
index 190b315f1..ea5ba9e52 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.c
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.c
@@ -136,12 +136,26 @@ void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_
}
effective_pwm[i] = output[i] * (max_pwm[i] - ramp_min_pwm)/2 + (max_pwm[i] + ramp_min_pwm)/2;
+
+ /* last line of defense against invalid inputs */
+ if (effective_pwm[i] < ramp_min_pwm) {
+ effective_pwm[i] = ramp_min_pwm;
+ } else if (effective_pwm[i] > max_pwm[i]) {
+ effective_pwm[i] = max_pwm[i];
+ }
}
}
break;
case PWM_LIMIT_STATE_ON:
for (unsigned i=0; i<num_channels; i++) {
effective_pwm[i] = output[i] * (max_pwm[i] - min_pwm[i])/2 + (max_pwm[i] + min_pwm[i])/2;
+
+ /* last line of defense against invalid inputs */
+ if (effective_pwm[i] < min_pwm[i]) {
+ effective_pwm[i] = min_pwm[i];
+ } else if (effective_pwm[i] > max_pwm[i]) {
+ effective_pwm[i] = max_pwm[i];
+ }
}
break;
default:
diff --git a/src/modules/systemlib/rc_check.c b/src/modules/systemlib/rc_check.c
index 21e15ec56..c0c1a5cb4 100644
--- a/src/modules/systemlib/rc_check.c
+++ b/src/modules/systemlib/rc_check.c
@@ -140,7 +140,7 @@ int rc_calibration_check(int mavlink_fd) {
/* sanity checks pass, enable channel */
if (count) {
mavlink_log_critical(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
- warnx(mavlink_fd, "ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
+ warnx("ERROR: %d config error(s) for RC channel %d.", count, (i + 1));
usleep(100000);
}
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index a23d89cd2..910b8a623 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -64,22 +64,40 @@ struct manual_control_setpoint_s {
/**
* Any of the channels may not be available and be set to NaN
* to indicate that it does not contain valid data.
+ * The variable names follow the definition of the
+ * MANUAL_CONTROL mavlink message.
+ * The default range is from -1 to 1 (mavlink message -1000 to 1000)
+ * The range for the z variable is defined from 0 to 1. (The z field of
+ * the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
*/
- float roll; /**< ailerons roll / roll rate input, -1..1 */
- float pitch; /**< elevator / pitch / pitch rate, -1..1 */
- float yaw; /**< rudder / yaw rate / yaw, -1..1 */
- float throttle; /**< throttle / collective thrust / altitude, 0..1 */
+ float x; /**< stick position in x direction -1..1
+ in general corresponds to forward/back motion or pitch of vehicle,
+ in general a positive value means forward or negative pitch and
+ a negative value means backward or positive pitch */
+ float y; /**< stick position in y direction -1..1
+ in general corresponds to right/left motion or roll of vehicle,
+ in general a positive value means right or positive roll and
+ a negative value means left or negative roll */
+ float z; /**< throttle stick position 0..1
+ in general corresponds to up/down motion or thrust of vehicle,
+ in general the value corresponds to the demanded throttle by the user,
+ if the input is used for setting the setpoint of a vertical position
+ controller any value > 0.5 means up and any value < 0.5 means down */
+ float r; /**< yaw stick/twist positon, -1..1
+ in general corresponds to the righthand rotation around the vertical
+ (downwards) axis of the vehicle */
float flaps; /**< flap position */
- float aux1; /**< default function: camera yaw / azimuth */
- float aux2; /**< default function: camera pitch / tilt */
- float aux3; /**< default function: camera trigger */
- float aux4; /**< default function: camera roll */
- float aux5; /**< default function: payload drop */
+ float aux1; /**< default function: camera yaw / azimuth */
+ float aux2; /**< default function: camera pitch / tilt */
+ float aux3; /**< default function: camera trigger */
+ float aux4; /**< default function: camera roll */
+ float aux5; /**< default function: payload drop */
- switch_pos_t mode_switch; /**< mode 3 position switch (mandatory): manual, assisted, auto */
- switch_pos_t return_switch; /**< land 2 position switch (mandatory): land, no effect */
- switch_pos_t assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
- switch_pos_t loiter_switch; /**< mission 2 position switch (optional): mission, loiter */
+ switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
+ switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
+ switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
+ switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
+ switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index c168b2fac..370c54442 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -45,12 +45,12 @@
/**
* The number of RC channel inputs supported.
* Current (Q4/2013) radios support up to 18 channels,
- * leaving at a sane value of 15.
+ * leaving at a sane value of 16.
* This number can be greater then number of RC channels,
* because single RC channel can be mapped to multiple
* functions, e.g. for various mode switches.
*/
-#define RC_CHANNELS_MAPPED_MAX 15
+#define RC_CHANNELS_MAPPED_MAX 16
/**
* This defines the mapping of the RC functions.
@@ -64,15 +64,16 @@ enum RC_CHANNELS_FUNCTION {
YAW = 3,
MODE = 4,
RETURN = 5,
- ASSISTED = 6,
+ POSCTL = 6,
LOITER = 7,
OFFBOARD_MODE = 8,
- FLAPS = 9,
- AUX_1 = 10,
- AUX_2 = 11,
- AUX_3 = 12,
- AUX_4 = 13,
- AUX_5 = 14,
+ ACRO = 9,
+ FLAPS = 10,
+ AUX_1 = 11,
+ AUX_2 = 12,
+ AUX_3 = 13,
+ AUX_4 = 14,
+ AUX_5 = 15,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
index 794c3f8bc..5924a324d 100644
--- a/src/modules/uORB/topics/vehicle_gps_position.h
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -68,6 +68,9 @@ struct vehicle_gps_position_s {
float eph_m; /**< GPS HDOP horizontal dilution of position in m */
float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ unsigned noise_per_ms; /**< */
+ unsigned jamming_indicator; /**< */
+
uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
float vel_m_s; /**< GPS ground speed (m/s) */
float vel_n_m_s; /**< GPS ground speed in m/s */
@@ -85,7 +88,7 @@ struct vehicle_gps_position_s {
uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
- uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
+ uint8_t satellite_snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */
bool satellite_info_available; /**< 0 for no info, 1 for info available */
};
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index a15303ea4..5d39c897d 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -83,6 +83,8 @@ struct vehicle_local_position_s {
float dist_bottom_rate; /**< Distance to bottom surface (ground) change rate */
uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
+ float eph;
+ float epv;
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 435230432..ea20a317a 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -63,9 +63,10 @@
/* main state machine */
typedef enum {
MAIN_STATE_MANUAL = 0,
- MAIN_STATE_SEATBELT,
- MAIN_STATE_EASY,
+ MAIN_STATE_ALTCTL,
+ MAIN_STATE_POSCTL,
MAIN_STATE_AUTO,
+ MAIN_STATE_ACRO,
MAIN_STATE_MAX
} main_state_t;
diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c
index e6d4b763b..4a97d328c 100644
--- a/src/systemcmds/config/config.c
+++ b/src/systemcmds/config/config.c
@@ -1,8 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
- * Author: Julian Oes <joes@student.ethz.ch>
+ * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -94,7 +92,6 @@ do_device(int argc, char *argv[])
}
int fd;
- int ret;
fd = open(argv[0], 0);
@@ -104,6 +101,8 @@ do_device(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[1], "block")) {
/* disable the device publications */
@@ -132,7 +131,6 @@ static void
do_gyro(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(GYRO_DEVICE_PATH, 0);
@@ -142,6 +140,8 @@ do_gyro(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the gyro internal sampling rate up to at least i Hz */
@@ -173,8 +173,13 @@ do_gyro(int argc, char *argv[])
warnx("gyro self test FAILED! Check calibration:");
struct gyro_scale scale;
ret = ioctl(fd, GYROIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(1, "failed getting gyro scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("gyro calibration and self test OK");
}
@@ -199,7 +204,6 @@ static void
do_mag(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(MAG_DEVICE_PATH, 0);
@@ -209,6 +213,8 @@ do_mag(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the mag internal sampling rate up to at least i Hz */
@@ -240,8 +246,13 @@ do_mag(int argc, char *argv[])
warnx("mag self test FAILED! Check calibration:");
struct mag_scale scale;
ret = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(ret, "failed getting mag scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("mag calibration and self test OK");
}
@@ -266,7 +277,6 @@ static void
do_accel(int argc, char *argv[])
{
int fd;
- int ret;
fd = open(ACCEL_DEVICE_PATH, 0);
@@ -276,6 +286,8 @@ do_accel(int argc, char *argv[])
} else {
+ int ret;
+
if (argc == 2 && !strcmp(argv[0], "sampling")) {
/* set the accel internal sampling rate up to at least i Hz */
@@ -307,8 +319,13 @@ do_accel(int argc, char *argv[])
warnx("accel self test FAILED! Check calibration:");
struct accel_scale scale;
ret = ioctl(fd, ACCELIOCGSCALE, (long unsigned int)&scale);
- warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_offset, scale.y_offset, scale.z_offset);
- warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", scale.x_scale, scale.y_scale, scale.z_scale);
+
+ if (ret) {
+ err(ret, "failed getting accel scale");
+ }
+
+ warnx("offsets: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_offset, (double)scale.y_offset, (double)scale.z_offset);
+ warnx("scale: X: % 9.6f Y: % 9.6f Z: % 9.6f", (double)scale.x_scale, (double)scale.y_scale, (double)scale.z_scale);
} else {
warnx("accel calibration and self test OK");
}
diff --git a/src/systemcmds/esc_calib/esc_calib.c b/src/systemcmds/esc_calib/esc_calib.c
index ad1996694..7d80af307 100644
--- a/src/systemcmds/esc_calib/esc_calib.c
+++ b/src/systemcmds/esc_calib/esc_calib.c
@@ -182,7 +182,7 @@ esc_calib_main(int argc, char *argv[])
if (orb_updated) {
errx(1, "ABORTING! Attitude control still active. Please ensure to shut down all controllers:\n"
- "\tmultirotor_att_control stop\n"
+ "\tmc_att_control stop\n"
"\tfw_att_control stop\n");
}
diff --git a/src/systemcmds/hw_ver/hw_ver.c b/src/systemcmds/hw_ver/hw_ver.c
deleted file mode 100644
index 4b84523cc..000000000
--- a/src/systemcmds/hw_ver/hw_ver.c
+++ /dev/null
@@ -1,73 +0,0 @@
-/****************************************************************************
- *
- * 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 hw_ver.c
- *
- * Show and test hardware version.
- */
-
-#include <nuttx/config.h>
-
-#include <stdio.h>
-#include <string.h>
-#include <errno.h>
-#include <version/version.h>
-
-__EXPORT int hw_ver_main(int argc, char *argv[]);
-
-int
-hw_ver_main(int argc, char *argv[])
-{
- if (argc >= 2) {
- if (!strcmp(argv[1], "show")) {
- printf(HW_ARCH "\n");
- exit(0);
- }
-
- if (!strcmp(argv[1], "compare")) {
- if (argc >= 3) {
- int ret = strcmp(HW_ARCH, argv[2]) != 0;
- if (ret == 0) {
- printf("hw_ver match: %s\n", HW_ARCH);
- }
- exit(ret);
-
- } else {
- errx(1, "not enough arguments, try 'compare PX4FMU_1'");
- }
- }
- }
-
- errx(1, "expected a command, try 'show' or 'compare'");
-}
diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c
index e34be44e3..a3f9dffff 100644
--- a/src/systemcmds/mtd/24xxxx_mtd.c
+++ b/src/systemcmds/mtd/24xxxx_mtd.c
@@ -142,12 +142,9 @@ struct at24c_dev_s {
uint16_t pagesize; /* 32, 63 */
uint16_t npages; /* 128, 256, 512, 1024 */
- perf_counter_t perf_reads;
- perf_counter_t perf_writes;
- perf_counter_t perf_resets;
- perf_counter_t perf_read_retries;
- perf_counter_t perf_read_errors;
- perf_counter_t perf_write_errors;
+ perf_counter_t perf_transfers;
+ perf_counter_t perf_resets_retries;
+ perf_counter_t perf_errors;
};
/************************************************************************************
@@ -298,9 +295,9 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
for (;;) {
- perf_begin(priv->perf_reads);
+ perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
- perf_end(priv->perf_reads);
+ perf_end(priv->perf_transfers);
if (ret >= 0)
break;
@@ -314,10 +311,10 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
* XXX maybe do special first-read handling with optional
* bus reset as well?
*/
- perf_count(priv->perf_read_retries);
+ perf_count(priv->perf_resets_retries);
if (--tries == 0) {
- perf_count(priv->perf_read_errors);
+ perf_count(priv->perf_errors);
return ERROR;
}
}
@@ -383,9 +380,9 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
for (;;) {
- perf_begin(priv->perf_writes);
+ perf_begin(priv->perf_transfers);
ret = I2C_TRANSFER(priv->dev, &msgv[0], 1);
- perf_end(priv->perf_writes);
+ perf_end(priv->perf_transfers);
if (ret >= 0)
break;
@@ -397,7 +394,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
* poll for write completion.
*/
if (--tries == 0) {
- perf_count(priv->perf_write_errors);
+ perf_count(priv->perf_errors);
return ERROR;
}
}
@@ -521,12 +518,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
priv->mtd.ioctl = at24c_ioctl;
priv->dev = dev;
- priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read");
- priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write");
- priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset");
- priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries");
- priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors");
- priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors");
+ priv->perf_transfers = perf_alloc(PC_ELAPSED, "eeprom_trans");
+ priv->perf_resets_retries = perf_alloc(PC_COUNT, "eeprom_rst");
+ priv->perf_errors = perf_alloc(PC_COUNT, "eeprom_errs");
}
/* attempt to read to validate device is present */
@@ -548,9 +542,9 @@ FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
}
};
- perf_begin(priv->perf_reads);
+ perf_begin(priv->perf_transfers);
int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
- perf_end(priv->perf_reads);
+ perf_end(priv->perf_transfers);
if (ret < 0) {
return NULL;
diff --git a/src/systemcmds/mtd/mtd.c b/src/systemcmds/mtd/mtd.c
index 0a88d40f3..a57eaafe7 100644
--- a/src/systemcmds/mtd/mtd.c
+++ b/src/systemcmds/mtd/mtd.c
@@ -160,7 +160,11 @@ static void
ramtron_attach(void)
{
/* find the right spi */
+#ifdef CONFIG_ARCH_BOARD_AEROCORE
+ struct spi_dev_s *spi = up_spiinitialize(4);
+#else
struct spi_dev_s *spi = up_spiinitialize(2);
+#endif
/* this resets the spi bus, set correct bus speed again */
SPI_SETFREQUENCY(spi, 10 * 1000 * 1000);
SPI_SETBITS(spi, 8);
diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk
index a48588535..b22b446da 100644
--- a/src/systemcmds/nshterm/module.mk
+++ b/src/systemcmds/nshterm/module.mk
@@ -38,4 +38,4 @@
MODULE_COMMAND = nshterm
SRCS = nshterm.c
-MODULE_STACKSIZE = 3000
+MODULE_STACKSIZE = 1200
diff --git a/src/systemcmds/param/module.mk b/src/systemcmds/param/module.mk
index 63f15ad28..f716eb71e 100644
--- a/src/systemcmds/param/module.mk
+++ b/src/systemcmds/param/module.mk
@@ -38,7 +38,8 @@
MODULE_COMMAND = param
SRCS = param.c
-MODULE_STACKSIZE = 4096
+# Note: measurements yielded a max of 900 bytes used.
+MODULE_STACKSIZE = 1800
MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c
index 0cbba0a37..d92ee88ef 100644
--- a/src/systemcmds/param/param.c
+++ b/src/systemcmds/param/param.c
@@ -61,8 +61,9 @@ static void do_load(const char* param_file_name);
static void do_import(const char* param_file_name);
static void do_show(const char* search_string);
static void do_show_print(void *arg, param_t param);
-static void do_set(const char* name, const char* val);
+static void do_set(const char* name, const char* val, bool fail_on_not_found);
static void do_compare(const char* name, const char* vals[], unsigned comparisons);
+static void do_reset();
int
param_main(int argc, char *argv[])
@@ -116,10 +117,17 @@ param_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "set")) {
- if (argc >= 4) {
- do_set(argv[2], argv[3]);
+ if (argc >= 5) {
+
+ /* if the fail switch is provided, fails the command if not found */
+ bool fail = !strcmp(argv[4], "fail");
+
+ do_set(argv[2], argv[3], fail);
+
+ } else if (argc >= 4) {
+ do_set(argv[2], argv[3], false);
} else {
- errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3'");
+ errx(1, "not enough arguments.\nTry 'param set PARAM_NAME 3 [fail]'");
}
}
@@ -130,6 +138,10 @@ param_main(int argc, char *argv[])
errx(1, "not enough arguments.\nTry 'param compare PARAM_NAME 3'");
}
}
+
+ if (!strcmp(argv[1], "reset")) {
+ do_reset();
+ }
}
errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'");
@@ -277,7 +289,7 @@ do_show_print(void *arg, param_t param)
}
static void
-do_set(const char* name, const char* val)
+do_set(const char* name, const char* val, bool fail_on_not_found)
{
int32_t i;
float f;
@@ -285,8 +297,8 @@ do_set(const char* name, const char* val)
/* set nothing if parameter cannot be found */
if (param == PARAM_INVALID) {
- /* param not found */
- errx(1, "Error: Parameter %s not found.", name);
+ /* param not found - fail silenty in scripts as it prevents booting */
+ errx(((fail_on_not_found) ? 1 : 0), "Error: Parameter %s not found.", name);
}
printf("%c %s: ",
@@ -402,3 +414,16 @@ do_compare(const char* name, const char* vals[], unsigned comparisons)
exit(ret);
}
+
+static void
+do_reset()
+{
+ param_reset_all();
+
+ if (param_save_default()) {
+ warnx("Param export failed.");
+ exit(1);
+ } else {
+ exit(0);
+ }
+}
diff --git a/src/systemcmds/perf/module.mk b/src/systemcmds/perf/module.mk
index 77952842b..ec39a7a85 100644
--- a/src/systemcmds/perf/module.mk
+++ b/src/systemcmds/perf/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = perf
SRCS = perf.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/perf/perf.c b/src/systemcmds/perf/perf.c
index b69ea597b..b08a2e3b7 100644
--- a/src/systemcmds/perf/perf.c
+++ b/src/systemcmds/perf/perf.c
@@ -73,7 +73,7 @@ int perf_main(int argc, char *argv[])
return -1;
}
- perf_print_all();
+ perf_print_all(0 /* stdout */);
fflush(stdout);
return 0;
}
diff --git a/src/systemcmds/preflight_check/module.mk b/src/systemcmds/preflight_check/module.mk
index 7c3c88783..0cb2a4cd0 100644
--- a/src/systemcmds/preflight_check/module.mk
+++ b/src/systemcmds/preflight_check/module.mk
@@ -40,3 +40,5 @@ MODULE_COMMAND = preflight_check
SRCS = preflight_check.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/pwm/module.mk b/src/systemcmds/pwm/module.mk
index 4a23bba90..13a24150f 100644
--- a/src/systemcmds/pwm/module.mk
+++ b/src/systemcmds/pwm/module.mk
@@ -38,4 +38,4 @@
MODULE_COMMAND = pwm
SRCS = pwm.c
-MODULE_STACKSIZE = 4096
+MODULE_STACKSIZE = 1800
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index 7c23f38c2..1828c660f 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -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
@@ -443,6 +443,110 @@ pwm_main(int argc, char *argv[])
exit(0);
}
}
+ usleep(2000);
+ }
+ exit(0);
+
+
+ } else if (!strcmp(argv[1], "steps")) {
+
+ if (set_mask == 0) {
+ usage("no channels set");
+ }
+
+ /* get current servo values */
+ struct pwm_output_values last_spos;
+
+ for (unsigned i = 0; i < servo_count; i++) {
+
+ ret = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&last_spos.values[i]);
+ if (ret != OK)
+ err(1, "PWM_SERVO_GET(%d)", i);
+ }
+
+ /* perform PWM output */
+
+ /* Open console directly to grab CTRL-C signal */
+ struct pollfd fds;
+ fds.fd = 0; /* stdin */
+ fds.events = POLLIN;
+
+ warnx("Running 5 steps. WARNING! Motors will be live in 5 seconds\nPress any key to abort now.");
+ sleep(5);
+
+ unsigned off = 900;
+ unsigned idle = 1300;
+ unsigned full = 2000;
+ unsigned steps_timings_us[] = {2000, 5000, 20000, 50000};
+
+ unsigned phase = 0;
+ unsigned phase_counter = 0;
+ unsigned const phase_maxcount = 20;
+
+ for ( unsigned steps_timing_index = 0;
+ steps_timing_index < sizeof(steps_timings_us) / sizeof(steps_timings_us[0]);
+ steps_timing_index++ ) {
+
+ warnx("Sending step input with 0 to 100%% over a %u microseconds ramp", steps_timings_us[steps_timing_index]);
+
+ while (1) {
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+
+ unsigned val;
+
+ if (phase == 0) {
+ val = idle;
+ } else if (phase == 1) {
+ /* ramp - depending how steep it is this ramp will look instantaneous on the output */
+ val = idle + (full - idle) * (phase_maxcount / (float)phase_counter);
+ } else {
+ val = off;
+ }
+
+ ret = ioctl(fd, PWM_SERVO_SET(i), val);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+
+ /* abort on user request */
+ char c;
+ ret = poll(&fds, 1, 0);
+ if (ret > 0) {
+
+ int ret = read(0, &c, 1);
+ if (ret > 0) {
+ /* reset output to the last value */
+ for (unsigned i = 0; i < servo_count; i++) {
+ if (set_mask & 1<<i) {
+ ret = ioctl(fd, PWM_SERVO_SET(i), last_spos.values[i]);
+ if (ret != OK)
+ err(1, "PWM_SERVO_SET(%d)", i);
+ }
+ }
+ warnx("Key pressed, user abort\n");
+ exit(0);
+ }
+ }
+ if (phase == 1) {
+ usleep(steps_timings_us[steps_timing_index] / phase_maxcount);
+
+ } else if (phase == 0) {
+ usleep(50000);
+ } else if (phase == 2) {
+ usleep(50000);
+ } else {
+ break;
+ }
+
+ phase_counter++;
+
+ if (phase_counter > phase_maxcount) {
+ phase++;
+ phase_counter = 0;
+ }
+ }
}
exit(0);
diff --git a/src/systemcmds/reboot/module.mk b/src/systemcmds/reboot/module.mk
index 19f64af54..edf9d8b37 100644
--- a/src/systemcmds/reboot/module.mk
+++ b/src/systemcmds/reboot/module.mk
@@ -39,3 +39,5 @@ MODULE_COMMAND = reboot
SRCS = reboot.c
MAXOPTIMIZATION = -Os
+
+MODULE_STACKSIZE = 800
diff --git a/src/systemcmds/tests/test_mtd.c b/src/systemcmds/tests/test_mtd.c
index bac9efbdb..cdb4362ba 100644
--- a/src/systemcmds/tests/test_mtd.c
+++ b/src/systemcmds/tests/test_mtd.c
@@ -57,6 +57,8 @@
#define PARAM_FILE_NAME "/fs/mtd_params"
static int check_user_abort(int fd);
+static void print_fail(void);
+static void print_success(void);
int check_user_abort(int fd) {
/* check if user wants to abort */
@@ -126,7 +128,7 @@ test_mtd(int argc, char *argv[])
uint8_t write_buf[chunk_sizes[c]] __attribute__((aligned(64)));
/* fill write buffer with known values */
- for (int i = 0; i < sizeof(write_buf); i++) {
+ for (unsigned i = 0; i < sizeof(write_buf); i++) {
/* this will wrap, but we just need a known value with spacing */
write_buf[i] = i+11;
}
@@ -137,11 +139,14 @@ test_mtd(int argc, char *argv[])
int fd = open(PARAM_FILE_NAME, O_RDONLY);
int rret = read(fd, read_buf, chunk_sizes[c]);
close(fd);
+ if (rret <= 0) {
+ err(1, "read error");
+ }
fd = open(PARAM_FILE_NAME, O_WRONLY);
printf("printing 2 percent of the first chunk:\n");
- for (int i = 0; i < sizeof(read_buf) / 50; i++) {
+ for (unsigned i = 0; i < sizeof(read_buf) / 50; i++) {
printf("%02X", read_buf[i]);
}
printf("\n");
@@ -171,9 +176,9 @@ test_mtd(int argc, char *argv[])
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
- int rret = read(fd, read_buf, chunk_sizes[c]);
+ int rret2 = read(fd, read_buf, chunk_sizes[c]);
- if (rret != chunk_sizes[c]) {
+ if (rret2 != (int)chunk_sizes[c]) {
warnx("READ ERROR!");
print_fail();
return 1;
@@ -182,7 +187,7 @@ test_mtd(int argc, char *argv[])
/* compare value */
bool compare_ok = true;
- for (int j = 0; j < chunk_sizes[c]; j++) {
+ for (unsigned j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d", j);
print_fail();
@@ -211,7 +216,7 @@ test_mtd(int argc, char *argv[])
char ffbuf[64];
memset(ffbuf, 0xFF, sizeof(ffbuf));
int fd = open(PARAM_FILE_NAME, O_WRONLY);
- for (int i = 0; i < file_size / sizeof(ffbuf); i++) {
+ for (unsigned i = 0; i < file_size / sizeof(ffbuf); i++) {
int ret = write(fd, ffbuf, sizeof(ffbuf));
if (ret != sizeof(ffbuf)) {
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index fe22f6177..e3f26924f 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -235,7 +235,7 @@ test_perf(int argc, char *argv[])
printf("perf: expect count of 1\n");
perf_print_counter(ec);
printf("perf: expect at least two counters\n");
- perf_print_all();
+ perf_print_all(0);
perf_free(cc);
perf_free(ec);
diff --git a/src/systemcmds/top/module.mk b/src/systemcmds/top/module.mk
index 9239aafc3..548a09f85 100644
--- a/src/systemcmds/top/module.mk
+++ b/src/systemcmds/top/module.mk
@@ -38,7 +38,7 @@
MODULE_COMMAND = top
SRCS = top.c
-MODULE_STACKSIZE = 3000
+MODULE_STACKSIZE = 1700
MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/hw_ver/module.mk b/src/systemcmds/ver/module.mk
index 3cc08b6a1..2eeb80b61 100644
--- a/src/systemcmds/hw_ver/module.mk
+++ b/src/systemcmds/ver/module.mk
@@ -32,12 +32,13 @@
############################################################################
#
-# Show and test hardware version
+# "version" nsh-command displays version infromation for hw,sw, gcc,build etc
+# can be also included and used in own code via "ver.h"
#
-MODULE_COMMAND = hw_ver
-SRCS = hw_ver.c
+MODULE_COMMAND = ver
+SRCS = ver.c
-MODULE_STACKSIZE = 1024
+MODULE_STACKSIZE = 1024
-MAXOPTIMIZATION = -Os
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c
new file mode 100644
index 000000000..9ae080ee2
--- /dev/null
+++ b/src/systemcmds/ver/ver.c
@@ -0,0 +1,123 @@
+/****************************************************************************
+*
+* 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 ver.c
+*
+* Version command, unifies way of showing versions of HW, SW, Build, GCC
+* In case you want to add new version just extend version_main function
+*
+* @author Vladimir Kulla <ufon@kullaonline.net>
+*/
+
+#include <stdio.h>
+#include <string.h>
+#include <version/version.h>
+#include <systemlib/err.h>
+
+// string constants for version commands
+static const char sz_ver_hw_str[] = "hw";
+static const char sz_ver_hwcmp_str[] = "hwcmp";
+static const char sz_ver_git_str[] = "git";
+static const char sz_ver_bdate_str[] = "bdate";
+static const char sz_ver_gcc_str[] = "gcc";
+static const char sz_ver_all_str[] = "all";
+
+static void usage(const char *reason)
+{
+ if (reason != NULL) {
+ printf("%s\n", reason);
+ }
+
+ printf("usage: ver {hw|hwcmp|git|bdate|gcc|all}\n\n");
+}
+
+__EXPORT int ver_main(int argc, char *argv[]);
+
+int ver_main(int argc, char *argv[])
+{
+ int ret = 1; //defaults to an error
+
+ // first check if there are at least 2 params
+ if (argc >= 2) {
+ if (argv[1] != NULL) {
+ if (!strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) {
+ printf("%s\n", HW_ARCH);
+ ret = 0;
+
+ } else if (!strncmp(argv[1], sz_ver_hwcmp_str, sizeof(sz_ver_hwcmp_str))) {
+ if (argc >= 3 && argv[2] != NULL) {
+ // compare 3rd parameter with HW_ARCH string, in case of match, return 0
+ ret = strncmp(HW_ARCH, argv[2], strlen(HW_ARCH));
+
+ if (ret == 0) {
+ printf("ver hwcmp match: %s\n", HW_ARCH);
+ }
+
+ } else {
+ errx(1, "Not enough arguments, try 'ver hwcmp PX4FMU_V2'");
+ }
+
+ } else if (!strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) {
+ printf("%s\n", FW_GIT);
+ ret = 0;
+
+ } else if (!strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) {
+ printf("%s %s\n", __DATE__, __TIME__);
+ ret = 0;
+
+ } else if (!strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) {
+ printf("%s\n", __VERSION__);
+ ret = 0;
+
+ } else if (!strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str))) {
+ printf("HW arch: %s\n", HW_ARCH);
+ printf("Build datetime: %s %s\n", __DATE__, __TIME__);
+ printf("FW git-hash: %s\n", FW_GIT);
+ printf("GCC toolchain: %s\n", __VERSION__);
+ ret = 0;
+
+ } else {
+ errx(1, "unknown command.\n");
+ }
+
+ } else {
+ usage("Error, input parameter NULL.\n");
+ }
+
+ } else {
+ usage("Error, not enough parameters.");
+ }
+
+ return ret;
+}