aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp173
-rw-r--r--src/modules/commander/px4_custom_mode.h1
-rw-r--r--src/modules/commander/state_machine_helper.cpp30
-rw-r--r--src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp2
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.cpp606
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_23states.h20
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_utilities.cpp20
-rw-r--r--src/modules/ekf_att_pos_estimator/estimator_utilities.h3
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp32
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.cpp2
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h4
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp15
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp147
-rw-r--r--src/modules/mavlink/mavlink_receiver.h9
-rw-r--r--src/modules/mc_pos_control/mc_pos_control_main.cpp91
-rw-r--r--src/modules/navigator/loiter.cpp29
-rw-r--r--src/modules/navigator/loiter.h16
-rw-r--r--src/modules/navigator/mission.cpp319
-rw-r--r--src/modules/navigator/mission.h48
-rw-r--r--src/modules/navigator/mission_block.cpp77
-rw-r--r--src/modules/navigator/mission_block.h14
-rw-r--r--src/modules/navigator/module.mk1
-rw-r--r--src/modules/navigator/navigator.h11
-rw-r--r--src/modules/navigator/navigator_main.cpp22
-rw-r--r--src/modules/navigator/navigator_mode.cpp39
-rw-r--r--src/modules/navigator/navigator_mode.h17
-rw-r--r--src/modules/navigator/offboard.cpp129
-rw-r--r--src/modules/navigator/offboard.h72
-rw-r--r--src/modules/navigator/rtl.cpp75
-rw-r--r--src/modules/navigator/rtl.h22
-rw-r--r--src/modules/px4iofirmware/i2c.c3
-rw-r--r--src/modules/px4iofirmware/px4io.h4
-rw-r--r--src/modules/px4iofirmware/registers.c2
-rw-r--r--src/modules/px4iofirmware/sbus.c4
-rw-r--r--src/modules/sdlog2/sdlog2.c31
-rw-r--r--src/modules/sdlog2/sdlog2_format.h8
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h35
-rw-r--r--src/modules/sensors/sensor_params.c26
-rw-r--r--src/modules/sensors/sensors.cpp16
-rw-r--r--src/modules/systemlib/cpuload.c2
-rw-r--r--src/modules/systemlib/systemlib.c3
-rw-r--r--src/modules/uORB/objects_common.cpp5
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h1
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h2
-rw-r--r--src/modules/uORB/topics/position_setpoint_triplet.h10
-rw-r--r--src/modules/uORB/topics/rc_channels.h2
-rw-r--r--src/modules/uORB/topics/telemetry_status.h24
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_status.h4
49 files changed, 1595 insertions, 634 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index efa26eb97..2058cd92e 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -126,6 +126,7 @@ extern struct system_load_s system_load;
#define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */
#define RC_TIMEOUT 500000
#define DL_TIMEOUT 5 * 1000* 1000
+#define OFFBOARD_TIMEOUT 500000
#define DIFFPRESS_TIMEOUT 2000000
#define PRINT_INTERVAL 5000000
@@ -166,6 +167,7 @@ static struct vehicle_status_s status;
static struct actuator_armed_s armed;
static struct safety_s safety;
static struct vehicle_control_mode_s control_mode;
+static struct offboard_control_setpoint_s sp_offboard;
/* tasks waiting for low prio thread */
typedef enum {
@@ -439,6 +441,10 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
} else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
/* ACRO */
main_ret = main_state_transition(status, MAIN_STATE_ACRO);
+
+ } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
+ /* OFFBOARD */
+ main_ret = main_state_transition(status, MAIN_STATE_OFFBOARD);
}
} else {
@@ -472,7 +478,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
// 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);
+ mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", (double)cmd->param1);
} else {
@@ -634,7 +640,7 @@ int commander_thread_main(int argc, char *argv[])
/* welcome user */
warnx("starting");
- char *main_states_str[MAIN_STATE_MAX];
+ const char *main_states_str[MAIN_STATE_MAX];
main_states_str[MAIN_STATE_MANUAL] = "MANUAL";
main_states_str[MAIN_STATE_ALTCTL] = "ALTCTL";
main_states_str[MAIN_STATE_POSCTL] = "POSCTL";
@@ -642,8 +648,9 @@ int commander_thread_main(int argc, char *argv[])
main_states_str[MAIN_STATE_AUTO_LOITER] = "AUTO_LOITER";
main_states_str[MAIN_STATE_AUTO_RTL] = "AUTO_RTL";
main_states_str[MAIN_STATE_ACRO] = "ACRO";
+ main_states_str[MAIN_STATE_OFFBOARD] = "OFFBOARD";
- char *arming_states_str[ARMING_STATE_MAX];
+ const char *arming_states_str[ARMING_STATE_MAX];
arming_states_str[ARMING_STATE_INIT] = "INIT";
arming_states_str[ARMING_STATE_STANDBY] = "STANDBY";
arming_states_str[ARMING_STATE_ARMED] = "ARMED";
@@ -652,7 +659,7 @@ int commander_thread_main(int argc, char *argv[])
arming_states_str[ARMING_STATE_REBOOT] = "REBOOT";
arming_states_str[ARMING_STATE_IN_AIR_RESTORE] = "IN_AIR_RESTORE";
- char *nav_states_str[NAVIGATION_STATE_MAX];
+ const char *nav_states_str[NAVIGATION_STATE_MAX];
nav_states_str[NAVIGATION_STATE_MANUAL] = "MANUAL";
nav_states_str[NAVIGATION_STATE_ALTCTL] = "ALTCTL";
nav_states_str[NAVIGATION_STATE_POSCTL] = "POSCTL";
@@ -664,6 +671,7 @@ int commander_thread_main(int argc, char *argv[])
nav_states_str[NAVIGATION_STATE_LAND] = "LAND";
nav_states_str[NAVIGATION_STATE_DESCEND] = "DESCEND";
nav_states_str[NAVIGATION_STATE_TERMINATION] = "TERMINATION";
+ nav_states_str[NAVIGATION_STATE_OFFBOARD] = "OFFBOARD";
/* pthread for slow low prio thread */
pthread_t commander_low_prio_thread;
@@ -773,7 +781,7 @@ int commander_thread_main(int argc, char *argv[])
bool updated = false;
- bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+ rc_calibration_check(mavlink_fd);
/* Subscribe to safety topic */
int safety_sub = orb_subscribe(ORB_ID(safety));
@@ -793,13 +801,18 @@ int commander_thread_main(int argc, char *argv[])
/* Subscribe to offboard control data */
int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
- struct offboard_control_setpoint_s sp_offboard;
memset(&sp_offboard, 0, sizeof(sp_offboard));
- /* Subscribe to telemetry status */
- int telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
- struct telemetry_status_s telemetry;
- memset(&telemetry, 0, sizeof(telemetry));
+ /* Subscribe to telemetry status topics */
+ int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
+ uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM];
+ bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM];
+
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ telemetry_last_heartbeat[i] = 0;
+ telemetry_lost[i] = true;
+ }
/* Subscribe to global position */
int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position));
@@ -881,7 +894,6 @@ int commander_thread_main(int argc, char *argv[])
bool arming_state_changed = false;
bool main_state_changed = false;
bool failsafe_old = false;
- bool system_checked = false;
while (!thread_should_exit) {
@@ -929,7 +941,7 @@ int commander_thread_main(int argc, char *argv[])
status_changed = true;
/* re-check RC calibration */
- rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd));
+ rc_calibration_check(mavlink_fd);
}
/* navigation parameters */
@@ -938,15 +950,6 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
}
- /* Perform system checks (again) once params are loaded and MAVLink is up. */
- if (!system_checked && mavlink_fd &&
- (telemetry.heartbeat_time > 0) &&
- (hrt_elapsed_time(&telemetry.heartbeat_time) < 1 * 1000 * 1000)) {
-
- (void)rc_calibration_check(mavlink_fd);
- system_checked = true;
- }
-
orb_check(sp_man_sub, &updated);
if (updated) {
@@ -959,10 +962,39 @@ int commander_thread_main(int argc, char *argv[])
orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard);
}
- orb_check(telemetry_sub, &updated);
+ if (sp_offboard.timestamp != 0 &&
+ sp_offboard.timestamp + OFFBOARD_TIMEOUT > hrt_absolute_time()) {
+ if (status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = false;
+ status_changed = true;
+ }
+ } else {
+ if (!status.offboard_control_signal_lost) {
+ status.offboard_control_signal_lost = true;
+ status_changed = true;
+ }
+ }
- if (updated) {
- orb_copy(ORB_ID(telemetry_status), telemetry_sub, &telemetry);
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ orb_check(telemetry_subs[i], &updated);
+
+ if (updated) {
+ struct telemetry_status_s telemetry;
+ memset(&telemetry, 0, sizeof(telemetry));
+
+ orb_copy(telemetry_status_orb_id[i], telemetry_subs[i], &telemetry);
+
+ /* perform system checks when new telemetry link connected */
+ if (mavlink_fd &&
+ telemetry_last_heartbeat[i] == 0 &&
+ telemetry.heartbeat_time > 0 &&
+ hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) {
+
+ (void)rc_calibration_check(mavlink_fd);
+ }
+
+ telemetry_last_heartbeat[i] = telemetry.heartbeat_time;
+ }
}
orb_check(sensor_sub, &updated);
@@ -1366,18 +1398,35 @@ int commander_thread_main(int argc, char *argv[])
}
}
- /* data link check */
- if (hrt_absolute_time() < telemetry.heartbeat_time + DL_TIMEOUT) {
+ /* data links check */
+ bool have_link = false;
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) {
+ /* handle the case where data link was regained */
+ if (telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "#audio: data link %i regained", i);
+ telemetry_lost[i] = false;
+ }
+ have_link = true;
+
+ } else {
+ if (!telemetry_lost[i]) {
+ mavlink_log_critical(mavlink_fd, "#audio: data link %i lost", i);
+ telemetry_lost[i] = true;
+ }
+ }
+ }
+
+ if (have_link) {
/* handle the case where data link was regained */
if (status.data_link_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: data link regained");
status.data_link_lost = false;
status_changed = true;
}
} else {
if (!status.data_link_lost) {
- mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: DATA LINK LOST");
+ mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: ALL DATA LINKS LOST");
status.data_link_lost = true;
status_changed = true;
}
@@ -1642,6 +1691,18 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
/* set main state according to RC switches */
transition_result_t res = TRANSITION_DENIED;
+ /* offboard switch overrides main switch */
+ if (sp_man->offboard_switch == SWITCH_POS_ON) {
+ res = main_state_transition(status, MAIN_STATE_OFFBOARD);
+ if (res == TRANSITION_DENIED) {
+ print_reject_mode(status, "OFFBOARD");
+
+ } else {
+ return res;
+ }
+ }
+
+ /* offboard switched off or denied, check main mode switch */
switch (sp_man->mode_switch) {
case SWITCH_POS_NONE:
res = TRANSITION_NOT_CHANGED;
@@ -1718,6 +1779,13 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin
}
print_reject_mode(status, "AUTO_MISSION");
+
+ // fallback to LOITER if home position not set
+ res = main_state_transition(status, MAIN_STATE_AUTO_LOITER);
+
+ if (res != TRANSITION_DENIED) {
+ break; // changed successfully or already in this state
+ }
}
// fallback to POSCTL
@@ -1754,6 +1822,7 @@ set_control_mode()
/* TODO: check this */
control_mode.flag_external_manual_override_ok = !status.is_rotary_wing;
control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON;
+ control_mode.flag_control_offboard_enabled = false;
switch (status.nav_state) {
case NAVIGATION_STATE_MANUAL:
@@ -1792,6 +1861,54 @@ set_control_mode()
control_mode.flag_control_termination_enabled = false;
break;
+ case NAVIGATION_STATE_OFFBOARD:
+ control_mode.flag_control_manual_enabled = false;
+ control_mode.flag_control_auto_enabled = false;
+ control_mode.flag_control_offboard_enabled = true;
+
+ switch (sp_offboard.mode) {
+ case OFFBOARD_CONTROL_MODE_DIRECT_RATES:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true; /* XXX: hack for now */
+ control_mode.flag_control_velocity_enabled = true;
+ break;
+ case OFFBOARD_CONTROL_MODE_DIRECT_POSITION:
+ control_mode.flag_control_rates_enabled = true;
+ control_mode.flag_control_attitude_enabled = true;
+ control_mode.flag_control_altitude_enabled = true;
+ control_mode.flag_control_climb_rate_enabled = true;
+ control_mode.flag_control_position_enabled = true;
+ control_mode.flag_control_velocity_enabled = true;
+ break;
+ default:
+ control_mode.flag_control_rates_enabled = false;
+ control_mode.flag_control_attitude_enabled = false;
+ control_mode.flag_control_altitude_enabled = false;
+ control_mode.flag_control_climb_rate_enabled = false;
+ control_mode.flag_control_position_enabled = false;
+ control_mode.flag_control_velocity_enabled = false;
+ }
+ break;
+
case NAVIGATION_STATE_POSCTL:
control_mode.flag_control_manual_enabled = true;
control_mode.flag_control_auto_enabled = false;
diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h
index 7f5f93801..eaf309288 100644
--- a/src/modules/commander/px4_custom_mode.h
+++ b/src/modules/commander/px4_custom_mode.h
@@ -16,6 +16,7 @@ enum PX4_CUSTOM_MAIN_MODE {
PX4_CUSTOM_MAIN_MODE_POSCTL,
PX4_CUSTOM_MAIN_MODE_AUTO,
PX4_CUSTOM_MAIN_MODE_ACRO,
+ PX4_CUSTOM_MAIN_MODE_OFFBOARD,
};
enum PX4_CUSTOM_SUB_MODE_AUTO {
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index 423ce2f23..6b96e3a3f 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -271,7 +271,6 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
}
break;
- case MAIN_STATE_AUTO_MISSION:
case MAIN_STATE_AUTO_LOITER:
/* need global position estimate */
if (status->condition_global_position_valid) {
@@ -279,6 +278,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
}
break;
+ case MAIN_STATE_AUTO_MISSION:
case MAIN_STATE_AUTO_RTL:
/* need global position and home position */
if (status->condition_global_position_valid && status->condition_home_position_valid) {
@@ -286,6 +286,15 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta
}
break;
+ case MAIN_STATE_OFFBOARD:
+
+ /* need offboard signal */
+ if (!status->offboard_control_signal_lost) {
+ ret = TRANSITION_CHANGED;
+ }
+
+ break;
+
case MAIN_STATE_MAX:
default:
break;
@@ -584,6 +593,25 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en
}
break;
+ case MAIN_STATE_OFFBOARD:
+ /* require offboard control, otherwise stay where you are */
+ if (status->offboard_control_signal_lost && !status->rc_signal_lost) {
+ status->failsafe = true;
+
+ status->nav_state = NAVIGATION_STATE_POSCTL;
+ } else if (status->offboard_control_signal_lost && status->rc_signal_lost) {
+ status->failsafe = true;
+
+ if (status->condition_local_position_valid) {
+ status->nav_state = NAVIGATION_STATE_LAND;
+ } else if (status->condition_local_altitude_valid) {
+ status->nav_state = NAVIGATION_STATE_DESCEND;
+ } else {
+ status->nav_state = NAVIGATION_STATE_TERMINATION;
+ }
+ } else {
+ status->nav_state = NAVIGATION_STATE_OFFBOARD;
+ }
default:
break;
}
diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
index e4f805dc0..5d768b73d 100644
--- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
+++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp
@@ -1533,7 +1533,7 @@ FixedwingEstimator::start()
_estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 40,
- 6000,
+ 5000,
(main_t)&FixedwingEstimator::task_main_trampoline,
nullptr);
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
index deaaf55fe..f33a1d780 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp
@@ -25,6 +25,7 @@ AttPosEKF::AttPosEKF()
useAirspeed = true;
useCompass = true;
useRangeFinder = true;
+ useOpticalFlow = true;
numericalProtection = true;
refSet = false;
storeIndex = 0;
@@ -227,10 +228,22 @@ void AttPosEKF::CovariancePrediction(float dt)
// scale gyro bias noise when on ground to allow for faster bias estimation
for (uint8_t i=10; i<=12; i++) processNoise[i] = dt * dAngBiasSigma;
processNoise[13] = dVelBiasSigma;
- for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma;
- for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma;
- for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma;
- processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
+ if (!inhibitWindStates) {
+ for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma;
+ } else {
+ for (uint8_t i=14; i<=15; i++) processNoise[i] = 0;
+ }
+ if (!inhibitMagStates) {
+ for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma;
+ for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma;
+ } else {
+ for (uint8_t i=16; i<=21; i++) processNoise[i] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma;
+ } else {
+ processNoise[22] = 0;
+ }
// square all sigmas
for (unsigned i = 0; i < n_states; i++) processNoise[i] = sq(processNoise[i]);
@@ -842,30 +855,6 @@ void AttPosEKF::CovariancePrediction(float dt)
nextP[i][i] = nextP[i][i] + processNoise[i];
}
- // If on ground or no magnetometer fitted, inhibit magnetometer bias updates by
- // setting the coresponding covariance terms to zero.
- if (onGround || !useCompass)
- {
- zeroRows(nextP,16,21);
- zeroCols(nextP,16,21);
- }
-
- // If on ground or not using airspeed sensing, inhibit wind velocity
- // covariance growth.
- if (onGround || !useAirspeed)
- {
- zeroRows(nextP,14,15);
- zeroCols(nextP,14,15);
- }
-
- // If on ground, inhibit terrain offset updates by
- // setting the coresponding covariance terms to zero.
- if (onGround)
- {
- zeroRows(nextP,22,22);
- zeroCols(nextP,22,22);
- }
-
// If the total position variance exceds 1E6 (1000m), then stop covariance
// growth by setting the predicted to the previous values
// This prevent an ill conditioned matrix from occurring for long periods
@@ -882,48 +871,22 @@ void AttPosEKF::CovariancePrediction(float dt)
}
}
- if (onGround || staticMode) {
- // copy the portion of the variances we want to
- // propagate
- for (unsigned i = 0; i <= 13; i++) {
- P[i][i] = nextP[i][i];
- }
-
- // force symmetry for observable states
- // force zero for non-observable states
- for (unsigned i = 1; i < n_states; i++)
- {
- for (uint8_t j = 0; j < i; j++)
- {
- if ((i > 13) || (j > 13)) {
- P[i][j] = 0.0f;
- } else {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- }
- P[j][i] = P[i][j];
- }
- }
-
- } else {
-
- // Copy covariance
- for (unsigned i = 0; i < n_states; i++) {
- P[i][i] = nextP[i][i];
- }
+ // Copy covariance
+ for (unsigned i = 0; i < n_states; i++) {
+ P[i][i] = nextP[i][i];
+ }
- // force symmetry for observable states
- for (unsigned i = 1; i < n_states; i++)
+ // force symmetry for observable states
+ for (unsigned i = 1; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < i; j++)
{
- for (uint8_t j = 0; j < i; j++)
- {
- P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
- P[j][i] = P[i][j];
- }
+ P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]);
+ P[j][i] = P[i][j];
}
-
}
- ConstrainVariances();
+ ConstrainVariances();
}
void AttPosEKF::FuseVelposNED()
@@ -944,7 +907,7 @@ void AttPosEKF::FuseVelposNED()
bool fuseData[6] = {false,false,false,false,false,false};
uint8_t stateIndex;
uint8_t obsIndex;
- uint8_t indexLimit;
+ uint8_t indexLimit = 22;
// declare variables used by state and covariance update calculations
float velErr;
@@ -981,11 +944,6 @@ void AttPosEKF::FuseVelposNED()
R_OBS[4] = R_OBS[3];
R_OBS[5] = sq(posDSigma) + sq(posErr);
- // Set innovation variances to zero default
- for (uint8_t i = 0; i<=5; i++)
- {
- varInnovVelPos[i] = 0.0f;
- }
// calculate innovations and check GPS data validity using an innovation consistency check
if (fuseVelData)
{
@@ -1071,15 +1029,6 @@ void AttPosEKF::FuseVelposNED()
{
fuseData[5] = true;
}
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = 22;
- }
- else
- {
- indexLimit = 13;
- }
// Fuse measurements sequentially
for (obsIndex=0; obsIndex<=5; obsIndex++)
{
@@ -1113,6 +1062,22 @@ void AttPosEKF::FuseVelposNED()
if (obsIndex != 5) {
Kfusion[13] = 0;
}
+ // Don't update wind states if inhibited
+ if (inhibitWindStates) {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ // Don't update magnetic field states if inhibited
+ if (inhibitMagStates) {
+ for (uint8_t i = 16; i<=21; i++)
+ {
+ Kfusion[i] = 0;
+ }
+ }
+ // Don't update terrain state if inhibited
+ if (inhibitGndHgtState) {
+ Kfusion[22] = 0;
+ }
// Calculate state corrections and re-normalise the quaternions
for (uint8_t i = 0; i<=indexLimit; i++)
@@ -1179,7 +1144,6 @@ void AttPosEKF::FuseMagnetometer()
for (uint8_t i = 0; i < n_states; i++) {
H_MAG[i] = 0.0f;
}
- unsigned indexLimit;
// Perform sequential fusion of Magnetometer measurements.
// This assumes that the errors in the different components are
@@ -1189,19 +1153,6 @@ void AttPosEKF::FuseMagnetometer()
// associated with sequential fusion
if (useCompass && fuseMagData && (obsIndex < 3))
{
- // Limit range of states modified when on ground
- if(!onGround)
- {
- indexLimit = n_states;
- }
- else
- {
- indexLimit = 13 + 1;
- }
-
- // Sequential fusion of XYZ components to spread processing load across
- // three prediction time steps.
-
// Calculate observation jacobians and Kalman gains
if (obsIndex == 0)
{
@@ -1287,15 +1238,31 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MX[0]*(P[12][19] + P[12][1]*SH_MAG[0] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[3] - P[12][2]*SK_MX[2] - P[12][16]*SK_MX[1] + P[12][17]*SK_MX[5] - P[12][18]*SK_MX[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MX[0]*(P[13][19] + P[13][1]*SH_MAG[0] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[3] - P[13][2]*SK_MX[2] - P[13][16]*SK_MX[1] + P[13][17]*SK_MX[5] - P[13][18]*SK_MX[4]);
- Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]);
- Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]);
- Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]);
- Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]);
- Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]);
- Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]);
- Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]);
- Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]);
- Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]);
+ Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]);
+ Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]);
+ Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]);
+ Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]);
+ Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]);
+ Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]);
+ } else {
+ for (uint8_t i=16; i <= 21; i++) {
+ Kfusion[i] = 0;
+ }
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovMag[0] = 1.0f/SK_MX[0];
innovMag[0] = MagPred[0] - magData.x;
}
@@ -1342,15 +1309,34 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MY[0]*(P[12][20] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][17]*SK_MY[1] - P[12][16]*SK_MY[3] + P[12][18]*SK_MY[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MY[0]*(P[13][20] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][17]*SK_MY[1] - P[13][16]*SK_MY[3] + P[13][18]*SK_MY[4]);
- Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]);
- Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]);
- Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]);
- Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]);
- Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]);
- Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]);
- Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]);
- Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]);
- Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]);
+ Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]);
+ Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]);
+ Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]);
+ Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]);
+ Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]);
+ Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]);
+ } else {
+ Kfusion[16] = 0;
+ Kfusion[17] = 0;
+ Kfusion[18] = 0;
+ Kfusion[19] = 0;
+ Kfusion[20] = 0;
+ Kfusion[21] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovMag[1] = 1.0f/SK_MY[0];
innovMag[1] = MagPred[1] - magData.y;
}
@@ -1398,15 +1384,34 @@ void AttPosEKF::FuseMagnetometer()
Kfusion[12] = SK_MZ[0]*(P[12][21] + P[12][0]*SH_MAG[1] + P[12][3]*SH_MAG[0] - P[12][1]*SK_MZ[2] + P[12][2]*SK_MZ[3] + P[12][18]*SK_MZ[1] + P[12][16]*SK_MZ[5] - P[12][17]*SK_MZ[4]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_MZ[0]*(P[13][21] + P[13][0]*SH_MAG[1] + P[13][3]*SH_MAG[0] - P[13][1]*SK_MZ[2] + P[13][2]*SK_MZ[3] + P[13][18]*SK_MZ[1] + P[13][16]*SK_MZ[5] - P[13][17]*SK_MZ[4]);
- Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]);
- Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]);
- Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]);
- Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]);
- Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]);
- Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]);
- Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]);
- Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]);
- Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]);
+ Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]);
+ Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]);
+ Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]);
+ Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]);
+ Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]);
+ Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]);
+ } else {
+ Kfusion[16] = 0;
+ Kfusion[17] = 0;
+ Kfusion[18] = 0;
+ Kfusion[19] = 0;
+ Kfusion[20] = 0;
+ Kfusion[21] = 0;
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovMag[2] = 1.0f/SK_MZ[0];
innovMag[2] = MagPred[2] - magData.z;
@@ -1416,7 +1421,7 @@ void AttPosEKF::FuseMagnetometer()
if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0f)
{
// correct the state vector
- for (uint8_t j= 0; j < indexLimit; j++)
+ for (uint8_t j= 0; j < n_states; j++)
{
states[j] = states[j] - Kfusion[j] * innovMag[obsIndex];
}
@@ -1433,7 +1438,7 @@ void AttPosEKF::FuseMagnetometer()
// correct the covariance P = (I - K*H)*P
// take advantage of the empty columns in KH to reduce the
// number of operations
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
for (uint8_t j = 0; j <= 3; j++)
{
@@ -1455,9 +1460,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j < indexLimit; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
KHP[i][j] = 0.0f;
for (uint8_t k = 0; k <= 3; k++)
@@ -1474,9 +1479,9 @@ void AttPosEKF::FuseMagnetometer()
}
}
}
- for (uint8_t i = 0; i < indexLimit; i++)
+ for (uint8_t i = 0; i < n_states; i++)
{
- for (uint8_t j = 0; j < indexLimit; j++)
+ for (uint8_t j = 0; j < n_states; j++)
{
P[i][j] = P[i][j] - KHP[i][j];
}
@@ -1552,15 +1557,31 @@ void AttPosEKF::FuseAirspeed()
Kfusion[12] = SK_TAS*(P[12][4]*SH_TAS[2] - P[12][14]*SH_TAS[2] + P[12][5]*SH_TAS[1] - P[12][15]*SH_TAS[1] + P[12][6]*vd*SH_TAS[0]);
// Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate
Kfusion[13] = 0.0f;//SK_TAS*(P[13][4]*SH_TAS[2] - P[13][14]*SH_TAS[2] + P[13][5]*SH_TAS[1] - P[13][15]*SH_TAS[1] + P[13][6]*vd*SH_TAS[0]);
- Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
- Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
- Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
- Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
- Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
- Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
- Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
- Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]);
- Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]);
+ // Estimation of selected states is inhibited by setting their Kalman gains to zero
+ if (!inhibitWindStates) {
+ Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]);
+ Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]);
+ } else {
+ Kfusion[14] = 0;
+ Kfusion[15] = 0;
+ }
+ if (!inhibitMagStates) {
+ Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]);
+ Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]);
+ Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]);
+ Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]);
+ Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]);
+ Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]);
+ } else {
+ for (uint8_t i=16; i <= 21; i++) {
+ Kfusion[i] = 0;
+ }
+ }
+ if (!inhibitGndHgtState) {
+ Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]);
+ } else {
+ Kfusion[22] = 0;
+ }
varInnovVtas = 1.0f/SK_TAS;
// Calculate the measurement innovation
@@ -1662,9 +1683,9 @@ void AttPosEKF::FuseRangeFinder()
float ptd = statesAtRngTime[22];
// Need to check that our range finder tilt angle is less than 30 degrees and we are using range finder data
- SH_RNG[4] = sin(rngFinderPitch);
+ SH_RNG[4] = sinf(rngFinderPitch);
cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cosf(rngFinderPitch);
- if (useRangeFinder && cosRngTilt > 0.87f)
+ if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f)
{
// Calculate observation jacobian and Kalman gain ignoring all states other than the terrain offset
// This prevents the range finder measurement modifying any of the other filter states and significantly reduces computations
@@ -1685,10 +1706,12 @@ void AttPosEKF::FuseRangeFinder()
SK_RNG[5] = SH_RNG[2];
Kfusion[22] = SK_RNG[0]*(P[22][9]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[22][0]*SH_RNG[1]*SK_RNG[2]*SK_RNG[5] - P[22][1]*SH_RNG[1]*SK_RNG[1]*SK_RNG[5] - P[22][2]*SH_RNG[1]*SK_RNG[4]*SK_RNG[5] + P[22][3]*SH_RNG[1]*SK_RNG[3]*SK_RNG[5]);
+ // Calculate the innovation variance for data logging
+ varInnovRng = 1.0f/SK_RNG[0];
+
// Calculate the measurement innovation
rngPred = (ptd - pd)/cosRngTilt;
innovRng = rngPred - rngMea;
- //printf("mea=%5.1f, pred=%5.1f, pd=%5.1f, ptd=%5.2f\n", rngMea, rngPred, pd, ptd);
// Check the innovation for consistency and don't fuse if > 5Sigma
if ((innovRng*innovRng*SK_RNG[0]) < 25)
@@ -1704,6 +1727,289 @@ void AttPosEKF::FuseRangeFinder()
}
+void AttPosEKF::FuseOptFlow()
+{
+ static uint8_t obsIndex;
+ static float SH_LOS[13];
+ static float SKK_LOS[15];
+ static float SK_LOS[2];
+ static float q0 = 0.0f;
+ static float q1 = 0.0f;
+ static float q2 = 0.0f;
+ static float q3 = 1.0f;
+ static float vn = 0.0f;
+ static float ve = 0.0f;
+ static float vd = 0.0f;
+ static float pd = 0.0f;
+ static float ptd = 0.0f;
+ static float R_LOS = 0.01f;
+ static float losPred[2];
+
+ // Transformation matrix from nav to body axes
+ Mat3f Tnb_local;
+ // Transformation matrix from body to sensor axes
+ // assume camera is aligned with Z body axis plus a misalignment
+ // defined by 3 small angles about X, Y and Z body axis
+ Mat3f Tbs;
+ Tbs.x.y = a3;
+ Tbs.y.x = -a3;
+ Tbs.x.z = -a2;
+ Tbs.z.x = a2;
+ Tbs.y.z = a1;
+ Tbs.z.y = -a1;
+ // Transformation matrix from navigation to sensor axes
+ Mat3f Tns;
+ float H_LOS[n_states];
+ for (uint8_t i = 0; i < n_states; i++) {
+ H_LOS[i] = 0.0f;
+ }
+ Vector3f velNED_local;
+ Vector3f relVelSensor;
+
+// Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg.
+ if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f)
+ {
+ // Sequential fusion of XY components to spread processing load across
+ // two prediction time steps.
+
+ // Calculate observation jacobians and Kalman gains
+ if (fuseOptFlowData)
+ {
+ // Copy required states to local variable names
+ q0 = statesAtOptFlowTime[0];
+ q1 = statesAtOptFlowTime[1];
+ q2 = statesAtOptFlowTime[2];
+ q3 = statesAtOptFlowTime[3];
+ vn = statesAtOptFlowTime[4];
+ ve = statesAtOptFlowTime[5];
+ vd = statesAtOptFlowTime[6];
+ pd = statesAtOptFlowTime[9];
+ ptd = statesAtOptFlowTime[22];
+ velNED_local.x = vn;
+ velNED_local.y = ve;
+ velNED_local.z = vd;
+
+ // calculate rotation from NED to body axes
+ float q00 = sq(q0);
+ float q11 = sq(q1);
+ float q22 = sq(q2);
+ float q33 = sq(q3);
+ float q01 = q0 * q1;
+ float q02 = q0 * q2;
+ float q03 = q0 * q3;
+ float q12 = q1 * q2;
+ float q13 = q1 * q3;
+ float q23 = q2 * q3;
+ Tnb_local.x.x = q00 + q11 - q22 - q33;
+ Tnb_local.y.y = q00 - q11 + q22 - q33;
+ Tnb_local.z.z = q00 - q11 - q22 + q33;
+ Tnb_local.y.x = 2*(q12 - q03);
+ Tnb_local.z.x = 2*(q13 + q02);
+ Tnb_local.x.y = 2*(q12 + q03);
+ Tnb_local.z.y = 2*(q23 - q01);
+ Tnb_local.x.z = 2*(q13 - q02);
+ Tnb_local.y.z = 2*(q23 + q01);
+
+ // calculate transformation from NED to sensor axes
+ Tns = Tbs*Tnb_local;
+
+ // calculate range from ground plain to centre of sensor fov assuming flat earth
+ float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f);
+
+ // calculate relative velocity in sensor frame
+ relVelSensor = Tns*velNED_local;
+
+ // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes
+ losPred[0] = relVelSensor.y/range;
+ losPred[1] = -relVelSensor.x/range;
+
+ //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y);
+ //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y);
+ //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range);
+
+ // Calculate observation jacobians
+ SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3);
+ SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+ SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+ SH_LOS[3] = 1/(pd - ptd);
+ SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2;
+ SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3;
+ SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1;
+ SH_LOS[7] = 1/sq(pd - ptd);
+ SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1;
+ SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0;
+ SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3;
+ SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0;
+ SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2;
+
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+ H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+ H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+ H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3);
+ H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+ H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3));
+ H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3));
+ H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3));
+ H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+ H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7];
+
+ // Calculate Kalman gain
+ SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3);
+ SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3);
+ SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3);
+ SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3);
+ SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3);
+ SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3);
+ SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]);
+ SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]);
+ SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]);
+ SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]);
+ SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+ SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+ SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+ SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]);
+ SKK_LOS[14] = SH_LOS[0];
+
+ SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]));
+ Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]);
+ varInnovOptFlow[0] = 1.0f/SK_LOS[0];
+ innovOptFlow[0] = losPred[0] - losData[0];
+
+ // reset the observation index to 0 (we start by fusing the X
+ // measurement)
+ obsIndex = 0;
+ fuseOptFlowData = false;
+ }
+ else if (obsIndex == 1) // we are now fusing the Y measurement
+ {
+ // Calculate observation jacobians
+ for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0;
+ H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]);
+ H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]);
+ H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]);
+ H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1);
+ H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3));
+ H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3));
+ H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3));
+ H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+ H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7];
+
+ // Calculate Kalman gains
+ SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]));
+ Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]);
+ varInnovOptFlow[1] = 1.0f/SK_LOS[1];
+ innovOptFlow[1] = losPred[1] - losData[1];
+ }
+
+ // Check the innovation for consistency and don't fuse if > 3Sigma
+ if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f)
+ {
+ // correct the state vector
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex];
+ }
+ // normalise the quaternion states
+ float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]);
+ if (quatMag > 1e-12f)
+ {
+ for (uint8_t j= 0; j<=3; j++)
+ {
+ float quatMagInv = 1.0f/quatMag;
+ states[j] = states[j] * quatMagInv;
+ }
+ }
+ // correct the covariance P = (I - K*H)*P
+ // take advantage of the empty columns in KH to reduce the
+ // number of operations
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j <= 6; j++)
+ {
+ KH[i][j] = Kfusion[i] * H_LOS[j];
+ }
+ for (uint8_t j = 7; j <= 8; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ KH[i][9] = Kfusion[i] * H_LOS[9];
+ for (uint8_t j = 10; j <= 21; j++)
+ {
+ KH[i][j] = 0.0f;
+ }
+ KH[i][22] = Kfusion[i] * H_LOS[22];
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ KHP[i][j] = 0.0f;
+ for (uint8_t k = 0; k <= 6; k++)
+ {
+ KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j];
+ }
+ KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j];
+ KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j];
+ }
+ }
+ }
+ for (uint8_t i = 0; i < n_states; i++)
+ {
+ for (uint8_t j = 0; j < n_states; j++)
+ {
+ P[i][j] = P[i][j] - KHP[i][j];
+ }
+ }
+ }
+ obsIndex = obsIndex + 1;
+ ForceSymmetry();
+ ConstrainVariances();
+}
+
void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last)
{
uint8_t row;
@@ -1904,6 +2210,24 @@ void AttPosEKF::OnGroundCheck()
if (staticMode) {
staticMode = (!refSet || (GPSstatus < GPS_FIX_3D));
}
+ // don't update wind states if there is no airspeed measurement
+ if (onGround || !useAirspeed) {
+ inhibitWindStates = true;
+ } else {
+ inhibitWindStates =false;
+ }
+ // don't update magnetic field states if on ground or not using compass
+ if (onGround || !useCompass) {
+ inhibitMagStates = true;
+ } else {
+ inhibitMagStates = false;
+ }
+ // don't update terrain offset state if on ground
+ if (onGround) {
+ inhibitGndHgtState = true;
+ } else {
+ inhibitGndHgtState = false;
+ }
}
void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude)
@@ -1931,8 +2255,8 @@ void AttPosEKF::CovarianceInit()
P[11][11] = P[10][10];
P[12][12] = P[10][10];
P[13][13] = sq(0.2f*dtIMU);
- P[14][14] = sq(8.0f);
- P[15][14] = P[14][14];
+ P[14][14] = sq(0.0f);
+ P[15][15] = P[14][14];
P[16][16] = sq(0.02f);
P[17][17] = P[16][16];
P[18][18] = P[16][16];
diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h
index 15ceb57c0..ff311649a 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_23states.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h
@@ -29,6 +29,10 @@ public:
float covDelAngMax; // maximum delta angle between covariance predictions
float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
+ float a1; // optical flow sensor misalgnment angle about X axis (rad)
+ float a2; // optical flow sensor misalgnment angle about Y axis (rad)
+ float a3; // optical flow sensor misalgnment angle about Z axis (rad)
+
float yawVarScale;
float windVelSigma;
float dAngBiasSigma;
@@ -55,6 +59,9 @@ public:
covDelAngMax = 0.02f; // maximum delta angle between covariance predictions
rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis.
EAS2TAS = 1.0f;
+ a1 = 0.0f; // optical flow sensor misalgnment angle about X axis (rad)
+ a2 = 0.0f; // optical flow sensor misalgnment angle about Y axis (rad)
+ a3 = 0.0f; // optical flow sensor misalgnment angle about Z axis (rad)
yawVarScale = 1.0f;
windVelSigma = 0.1f;
@@ -115,6 +122,7 @@ public:
float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time
float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time
float statesAtRngTime[n_states]; // filter states at the effective measurement time
+ float statesAtOptFlowTime[n_states]; // States at the effective optical flow measurement time
Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad)
Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s)
@@ -147,9 +155,13 @@ public:
float innovMag[3]; // innovation output
float varInnovMag[3]; // innovation variance output
Vector3f magData; // magnetometer flux radings in X,Y,Z body axes
+ float losData[2]; // optical flow LOS rate measurements (rad/sec)
float innovVtas; // innovation output
float innovRng; ///< Range finder innovation
+ float innovOptFlow[2]; // optical flow LOS innovations (rad/sec)
+ float varInnovOptFlow[2]; // optical flow innovations variances (rad/sec)^2
float varInnovVtas; // innovation variance output
+ float varInnovRng; // range finder innovation variance
float VtasMeas; // true airspeed measurement (m/s)
float magDeclination; ///< magnetic declination
double latRef; // WGS-84 latitude of reference point (rad)
@@ -178,12 +190,18 @@ public:
bool fuseMagData; // boolean true when magnetometer data is to be fused
bool fuseVtasData; // boolean true when airspeed data is to be fused
bool fuseRngData; ///< true when range data is fused
+ bool fuseOptFlowData; // true when optical flow data is fused
+
+ bool inhibitWindStates; // true when wind states and covariances are to remain constant
+ bool inhibitMagStates; // true when magnetic field states and covariances are to remain constant
+ bool inhibitGndHgtState; // true when the terrain ground height offset state and covariances are to remain constant
bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying)
bool staticMode; ///< boolean true if no position feedback is fused
bool useAirspeed; ///< boolean true if airspeed data is being used
bool useCompass; ///< boolean true if magnetometer data is being used
bool useRangeFinder; ///< true when rangefinder is being used
+ bool useOpticalFlow; // true when optical flow data is being used
bool ekfDiverged;
uint64_t lastReset;
@@ -208,7 +226,7 @@ void FuseAirspeed();
void FuseRangeFinder();
-void FuseOpticalFlow();
+void FuseOptFlow();
void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last);
diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
index b4767a0d3..29a8c8d1e 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
+++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp
@@ -8,6 +8,7 @@
#ifdef EKF_DEBUG
#include <stdio.h>
+#include <stdarg.h>
static void
ekf_debug_print(const char *fmt, va_list args)
@@ -101,6 +102,25 @@ Vector3f operator*( Mat3f matIn, Vector3f vecIn)
return vecOut;
}
+// overload * operator to provide a matrix product
+Mat3f operator*( Mat3f matIn1, Mat3f matIn2)
+{
+ Mat3f matOut;
+ matOut.x.x = matIn1.x.x*matIn2.x.x + matIn1.x.y*matIn2.y.x + matIn1.x.z*matIn2.z.x;
+ matOut.x.y = matIn1.x.x*matIn2.x.y + matIn1.x.y*matIn2.y.y + matIn1.x.z*matIn2.z.y;
+ matOut.x.z = matIn1.x.x*matIn2.x.z + matIn1.x.y*matIn2.y.z + matIn1.x.z*matIn2.z.z;
+
+ matOut.y.x = matIn1.y.x*matIn2.x.x + matIn1.y.y*matIn2.y.x + matIn1.y.z*matIn2.z.x;
+ matOut.y.y = matIn1.y.x*matIn2.x.y + matIn1.y.y*matIn2.y.y + matIn1.y.z*matIn2.z.y;
+ matOut.y.z = matIn1.y.x*matIn2.x.z + matIn1.y.y*matIn2.y.z + matIn1.y.z*matIn2.z.z;
+
+ matOut.z.x = matIn1.z.x*matIn2.x.x + matIn1.z.y*matIn2.y.x + matIn1.z.z*matIn2.z.x;
+ matOut.z.y = matIn1.z.x*matIn2.x.y + matIn1.z.y*matIn2.y.y + matIn1.z.z*matIn2.z.y;
+ matOut.z.z = matIn1.z.x*matIn2.x.z + matIn1.z.y*matIn2.y.z + matIn1.z.z*matIn2.z.z;
+
+ return matOut;
+}
+
// overload % operator to provide a vector cross product
Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2)
{
diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h
index d47568b62..5648cb05c 100644
--- a/src/modules/ekf_att_pos_estimator/estimator_utilities.h
+++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h
@@ -41,6 +41,7 @@ Vector3f operator*(float sclIn1, Vector3f vecIn1);
Vector3f operator+( Vector3f vecIn1, Vector3f vecIn2);
Vector3f operator-( Vector3f vecIn1, Vector3f vecIn2);
Vector3f operator*( Mat3f matIn, Vector3f vecIn);
+Mat3f operator*( Mat3f matIn1, Mat3f matIn2);
Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2);
Vector3f operator*(Vector3f vecIn1, float sclIn1);
@@ -79,4 +80,4 @@ struct ekf_status_report {
bool velOffsetExcessive;
};
-void ekf_debug(const char *fmt, ...); \ No newline at end of file
+void ekf_debug(const char *fmt, ...);
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 000c02e3d..3d6c62434 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
@@ -414,6 +414,17 @@ FixedwingPositionControl::FixedwingPositionControl() :
_attitude_sp_pub(-1),
_nav_capabilities_pub(-1),
+ _att(),
+ _att_sp(),
+ _nav_capabilities(),
+ _manual(),
+ _airspeed(),
+ _control_mode(),
+ _global_pos(),
+ _pos_sp_triplet(),
+ _sensor_combined(),
+ _range_finder(),
+
/* performance counters */
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
@@ -433,18 +444,8 @@ FixedwingPositionControl::FixedwingPositionControl() :
_airspeed_valid(false),
_groundspeed_undershoot(0.0f),
_global_pos_valid(false),
- _att(),
- _att_sp(),
- _nav_capabilities(),
- _manual(),
- _airspeed(),
- _control_mode(),
- _global_pos(),
- _pos_sp_triplet(),
- _sensor_combined(),
_mTecs(),
- _was_pos_control_mode(false),
- _range_finder()
+ _was_pos_control_mode(false)
{
_nav_capabilities.turn_distance = 0.0f;
@@ -806,12 +807,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
float eas2tas = 1.0f; // XXX calculate actual number based on current measurements
- // XXX re-visit
- float baro_altitude = _global_pos.alt;
-
/* filter speed and altitude for controller */
math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2);
- math::Vector<3> accel_earth = _R_nb * accel_body;
float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt;
@@ -944,8 +941,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
float airspeed_land = 1.3f * _parameters.airspeed_min;
float airspeed_approach = 1.3f * _parameters.airspeed_min;
- /* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */
- float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
+ /* Calculate altitude of last ordinary waypoint L */
float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f;
float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1));
@@ -1449,7 +1445,7 @@ FixedwingPositionControl::start()
_control_task = task_spawn_cmd("fw_pos_control_l1",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 5,
- 4048,
+ 3500,
(main_t)&FixedwingPositionControl::task_main_trampoline,
nullptr);
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
index fc0a2551c..2e37d166e 100644
--- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp
@@ -220,7 +220,7 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight
/* Apply overrride given by the limitOverride argument (this is used for limits which are not given by
* parameters such as pitch limits with takeoff waypoints or throttle limits when the launchdetector
* is running) */
- bool limitApplied = limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch);
+ limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch);
/* Write part of the status message */
_status.flightPathAngleSp = flightPathAngleSp;
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h
index e4e405227..c22e60ae0 100644
--- a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h
@@ -56,9 +56,9 @@ class BlockOutputLimiter: public SuperBlock
{
public:
// methods
- BlockOutputLimiter(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
+ BlockOutputLimiter(SuperBlock *parent, const char *name, bool fAngularLimit = false) :
SuperBlock(parent, name),
- _isAngularLimit(isAngularLimit),
+ _isAngularLimit(fAngularLimit),
_min(this, "MIN"),
_max(this, "MAX")
{};
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index ca846a465..57ae6076c 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -199,12 +199,18 @@ MavlinkFTP::ErrorCode
MavlinkFTP::_workList(Request *req)
{
auto hdr = req->header();
- DIR *dp = opendir(req->dataAsCString());
+
+ char dirPath[kMaxDataLength];
+ strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+
+ DIR *dp = opendir(dirPath);
if (dp == nullptr) {
- printf("FTP: can't open path '%s'\n", req->dataAsCString());
+ printf("FTP: can't open path '%s'\n", dirPath);
return kErrNotDir;
}
+
+ printf("FTP: list %s offset %d\n", dirPath, hdr->offset);
ErrorCode errorCode = kErrNone;
struct dirent entry, *result = nullptr;
@@ -216,6 +222,7 @@ MavlinkFTP::_workList(Request *req)
for (;;) {
// read the directory entry
if (readdir_r(dp, &entry, &result)) {
+ printf("FTP: list %s readdir_r failure\n", dirPath);
errorCode = kErrIO;
break;
}
@@ -251,8 +258,8 @@ MavlinkFTP::_workList(Request *req)
// copy the name, which we know will fit
strcpy((char *)&hdr->data[offset], entry.d_name);
+ //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
offset += strlen(entry.d_name) + 1;
- printf("FTP: list %s\n", entry.d_name);
}
closedir(dp);
@@ -346,7 +353,7 @@ MavlinkFTP::_workWrite(Request *req)
MavlinkFTP::ErrorCode
MavlinkFTP::_workRemove(Request *req)
{
- auto hdr = req->header();
+ //auto hdr = req->header();
// for now, send error reply
return kErrPerm;
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 6d361052c..81966caf8 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -102,18 +102,25 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_cmd_pub(-1),
_flow_pub(-1),
_offboard_control_sp_pub(-1),
+ _local_pos_sp_pub(-1),
+ _global_vel_sp_pub(-1),
+ _att_sp_pub(-1),
+ _rates_sp_pub(-1),
_vicon_position_pub(-1),
_telemetry_status_pub(-1),
_rc_pub(-1),
_manual_pub(-1),
_telemetry_heartbeat_time(0),
_radio_status_available(false),
+ _control_mode_sub(-1),
_hil_frames(0),
_old_timestamp(0),
_hil_local_proj_inited(0),
_hil_local_alt0(0.0)
{
+ _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
memset(&hil_local_pos, 0, sizeof(hil_local_pos));
+ memset(&_control_mode, 0, sizeof(_control_mode));
// make sure the FTP server is started
(void)MavlinkFTP::getServer();
@@ -359,53 +366,21 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg)
void
MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg)
{
- mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint;
- mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint);
+ mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control;
+ mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control);
- if (mavlink_system.sysid < 4) {
+ /* Only accept system IDs from 1 to 4 */
+ if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) {
struct offboard_control_setpoint_s offboard_control_sp;
memset(&offboard_control_sp, 0, sizeof(offboard_control_sp));
- uint8_t ml_mode = 0;
- bool ml_armed = false;
+ /* Convert values * 1000 back */
+ offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f;
+ offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f;
- switch (quad_motors_setpoint.mode) {
- case 0:
- ml_armed = false;
- break;
-
- case 1:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES;
- ml_armed = true;
-
- break;
-
- case 2:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE;
- ml_armed = true;
-
- break;
-
- case 3:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY;
- break;
-
- case 4:
- ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION;
- break;
- }
-
- offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX;
- offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX;
-
- if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) {
- ml_armed = false;
- }
-
- offboard_control_sp.armed = ml_armed;
- offboard_control_sp.mode = static_cast<enum OFFBOARD_CONTROL_MODE>(ml_mode);
+ offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode;
offboard_control_sp.timestamp = hrt_absolute_time();
@@ -421,32 +396,35 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message
void
MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
{
- mavlink_radio_status_t rstatus;
- mavlink_msg_radio_status_decode(msg, &rstatus);
-
- struct telemetry_status_s tstatus;
- memset(&tstatus, 0, sizeof(tstatus));
-
- tstatus.timestamp = hrt_absolute_time();
- tstatus.heartbeat_time = _telemetry_heartbeat_time;
- tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
- tstatus.rssi = rstatus.rssi;
- tstatus.remote_rssi = rstatus.remrssi;
- tstatus.txbuf = rstatus.txbuf;
- tstatus.noise = rstatus.noise;
- tstatus.remote_noise = rstatus.remnoise;
- tstatus.rxerrors = rstatus.rxerrors;
- tstatus.fixed = rstatus.fixed;
-
- if (_telemetry_status_pub < 0) {
- _telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);
+ /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
+ if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) {
+ mavlink_radio_status_t rstatus;
+ mavlink_msg_radio_status_decode(msg, &rstatus);
+
+ struct telemetry_status_s tstatus;
+ memset(&tstatus, 0, sizeof(tstatus));
+
+ tstatus.timestamp = hrt_absolute_time();
+ tstatus.heartbeat_time = _telemetry_heartbeat_time;
+ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO;
+ tstatus.rssi = rstatus.rssi;
+ tstatus.remote_rssi = rstatus.remrssi;
+ tstatus.txbuf = rstatus.txbuf;
+ tstatus.noise = rstatus.noise;
+ tstatus.remote_noise = rstatus.remnoise;
+ tstatus.rxerrors = rstatus.rxerrors;
+ tstatus.fixed = rstatus.fixed;
+
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
- } else {
- orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);
- }
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
+ }
- /* this means that heartbeats alone won't be published to the radio status no more */
- _radio_status_available = true;
+ /* this means that heartbeats alone won't be published to the radio status no more */
+ _radio_status_available = true;
+ }
}
void
@@ -464,6 +442,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
manual.r = man.r / 1000.0f;
manual.z = man.z / 1000.0f;
+ warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", manual.x, manual.y, manual.r, manual.z);
+
if (_manual_pub < 0) {
_manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual);
@@ -475,28 +455,31 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg)
void
MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg)
{
- mavlink_heartbeat_t hb;
- mavlink_msg_heartbeat_decode(msg, &hb);
+ /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */
+ if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) {
+ mavlink_heartbeat_t hb;
+ mavlink_msg_heartbeat_decode(msg, &hb);
- /* ignore own heartbeats, accept only heartbeats from GCS */
- if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) {
- _telemetry_heartbeat_time = hrt_absolute_time();
+ /* ignore own heartbeats, accept only heartbeats from GCS */
+ if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) {
+ _telemetry_heartbeat_time = hrt_absolute_time();
- /* if no radio status messages arrive, lets at least publish that heartbeats were received */
- if (!_radio_status_available) {
+ /* if no radio status messages arrive, lets at least publish that heartbeats were received */
+ if (!_radio_status_available) {
- struct telemetry_status_s tstatus;
- memset(&tstatus, 0, sizeof(tstatus));
+ struct telemetry_status_s tstatus;
+ memset(&tstatus, 0, sizeof(tstatus));
- tstatus.timestamp = _telemetry_heartbeat_time;
- tstatus.heartbeat_time = _telemetry_heartbeat_time;
- tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
+ tstatus.timestamp = _telemetry_heartbeat_time;
+ tstatus.heartbeat_time = _telemetry_heartbeat_time;
+ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC;
- if (_telemetry_status_pub < 0) {
- _telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus);
+ if (_telemetry_status_pub < 0) {
+ _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
- } else {
- orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus);
+ } else {
+ orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus);
+ }
}
}
}
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 040a07480..65ef884a2 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -36,6 +36,7 @@
* MAVLink 1.0 uORB listener definition
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#pragma once
@@ -44,6 +45,7 @@
#include <uORB/uORB.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/rc_channels.h>
+#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_gps_position.h>
#include <uORB/topics/vehicle_global_position.h>
@@ -53,6 +55,7 @@
#include <uORB/topics/offboard_control_setpoint.h>
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
+#include <uORB/topics/vehicle_global_velocity_setpoint.h>
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
@@ -124,6 +127,7 @@ private:
mavlink_status_t status;
struct vehicle_local_position_s hil_local_pos;
+ struct vehicle_control_mode_s _control_mode;
orb_advert_t _global_pos_pub;
orb_advert_t _local_pos_pub;
orb_advert_t _attitude_pub;
@@ -138,12 +142,17 @@ private:
orb_advert_t _cmd_pub;
orb_advert_t _flow_pub;
orb_advert_t _offboard_control_sp_pub;
+ orb_advert_t _local_pos_sp_pub;
+ orb_advert_t _global_vel_sp_pub;
+ orb_advert_t _att_sp_pub;
+ orb_advert_t _rates_sp_pub;
orb_advert_t _vicon_position_pub;
orb_advert_t _telemetry_status_pub;
orb_advert_t _rc_pub;
orb_advert_t _manual_pub;
hrt_abstime _telemetry_heartbeat_time;
bool _radio_status_available;
+ int _control_mode_sub;
int _hil_frames;
uint64_t _old_timestamp;
bool _hil_local_proj_inited;
diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp
index bcc3e2ae7..4e88e260c 100644
--- a/src/modules/mc_pos_control/mc_pos_control_main.cpp
+++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp
@@ -117,7 +117,9 @@ private:
int _manual_sub; /**< notification of manual control updates */
int _arming_sub; /**< arming status of outputs */
int _local_pos_sub; /**< vehicle local position */
- int _pos_sp_triplet_sub; /**< position setpoint triplet */
+ int _pos_sp_triplet_sub; /**< position setpoint triplet */
+ int _local_pos_sp_sub; /**< offboard local position setpoint */
+ int _global_vel_sp_sub; /**< offboard global velocity setpoint */
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */
@@ -133,6 +135,7 @@ private:
struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */
struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */
+
struct {
param_t thr_min;
param_t thr_max;
@@ -255,6 +258,7 @@ MulticopterPositionControl::MulticopterPositionControl() :
_manual_sub(-1),
_arming_sub(-1),
_local_pos_sub(-1),
+ _global_vel_sp_sub(-1),
_pos_sp_triplet_sub(-1),
/* publications */
@@ -528,6 +532,9 @@ MulticopterPositionControl::task_main()
_arming_sub = orb_subscribe(ORB_ID(actuator_armed));
_local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
_pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
+ _local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ _global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
+
parameters_update(true);
@@ -548,6 +555,9 @@ MulticopterPositionControl::task_main()
math::Vector<3> sp_move_rate;
sp_move_rate.zero();
+
+ float yaw_sp_move_rate;
+
math::Vector<3> thrust_int;
thrust_int.zero();
math::Matrix<3, 3> R;
@@ -663,6 +673,82 @@ MulticopterPositionControl::task_main()
_pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
}
+ } else if (_control_mode.flag_control_offboard_enabled) {
+ /* Offboard control */
+ bool updated;
+ orb_check(_pos_sp_triplet_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet);
+ }
+
+ if (_pos_sp_triplet.current.valid) {
+
+ if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) {
+
+ _pos_sp(0) = _pos_sp_triplet.current.x;
+ _pos_sp(1) = _pos_sp_triplet.current.y;
+ _pos_sp(2) = _pos_sp_triplet.current.z;
+ _att_sp.yaw_body = _pos_sp_triplet.current.yaw;
+
+ } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) {
+ /* reset position setpoint to current position if needed */
+ reset_pos_sp();
+ /* move position setpoint with roll/pitch stick */
+ sp_move_rate(0) = _pos_sp_triplet.current.vx;
+ sp_move_rate(1) = _pos_sp_triplet.current.vy;
+ yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed;
+ _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt;
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ /* reset alt setpoint to current altitude if needed */
+ reset_alt_sp();
+
+ /* move altitude setpoint with throttle stick */
+ sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);;
+ }
+
+ /* limit setpoint move rate */
+ float sp_move_norm = sp_move_rate.length();
+
+ if (sp_move_norm > 1.0f) {
+ sp_move_rate /= sp_move_norm;
+ }
+
+ /* scale to max speed and rotate around yaw */
+ math::Matrix<3, 3> R_yaw_sp;
+ R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body);
+ sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max);
+
+ /* move position setpoint */
+ _pos_sp += sp_move_rate * dt;
+
+ /* check if position setpoint is too far from actual position */
+ math::Vector<3> pos_sp_offs;
+ pos_sp_offs.zero();
+
+ if (_control_mode.flag_control_position_enabled) {
+ pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0);
+ pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1);
+ }
+
+ if (_control_mode.flag_control_altitude_enabled) {
+ pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2);
+ }
+
+ float pos_sp_offs_norm = pos_sp_offs.length();
+
+ if (pos_sp_offs_norm > 1.0f) {
+ pos_sp_offs /= pos_sp_offs_norm;
+ _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max);
+ }
+
+ } else {
+ reset_pos_sp();
+ reset_alt_sp();
+ }
+
} else {
/* AUTO */
bool updated;
@@ -709,6 +795,7 @@ MulticopterPositionControl::task_main()
_local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp);
}
+
if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid && _pos_sp_triplet.current.type == SETPOINT_TYPE_IDLE) {
/* idle state, don't run controller and set zero thrust */
R.identity();
@@ -752,6 +839,7 @@ MulticopterPositionControl::task_main()
_vel_sp(2) = _params.land_speed;
}
+
if (!_control_mode.flag_control_manual_enabled) {
/* limit 3D speed only in non-manual modes */
float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length();
@@ -1039,6 +1127,7 @@ MulticopterPositionControl::task_main()
_reset_pos_sp = true;
reset_int_z = true;
reset_int_xy = true;
+
}
/* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp
index 542483fb1..f827e70c9 100644
--- a/src/modules/navigator/loiter.cpp
+++ b/src/modules/navigator/loiter.cpp
@@ -36,6 +36,7 @@
* Helper class to loiter
*
* @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include <string.h>
@@ -51,28 +52,42 @@
#include <uORB/topics/position_setpoint_triplet.h>
#include "loiter.h"
+#include "navigator.h"
Loiter::Loiter(Navigator *navigator, const char *name) :
MissionBlock(navigator, name)
{
/* load initial params */
updateParams();
- /* initial reset */
- on_inactive();
}
Loiter::~Loiter()
{
}
-bool
-Loiter::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+void
+Loiter::on_inactive()
{
- /* set loiter item, don't reuse an existing position setpoint */
- return set_loiter_item(pos_sp_triplet);
}
void
-Loiter::on_inactive()
+Loiter::on_activation()
+{
+ /* set current mission item to loiter */
+ set_loiter_item(&_mission_item);
+
+ /* convert mission item to current setpoint */
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+ pos_sp_triplet->previous.valid = false;
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
+
+ _navigator->set_position_setpoint_triplet_updated();
+}
+
+void
+Loiter::on_active()
{
}
diff --git a/src/modules/navigator/loiter.h b/src/modules/navigator/loiter.h
index 65ff5c31e..37ab57a07 100644
--- a/src/modules/navigator/loiter.h
+++ b/src/modules/navigator/loiter.h
@@ -50,25 +50,15 @@
class Loiter : public MissionBlock
{
public:
- /**
- * Constructor
- */
Loiter(Navigator *navigator, const char *name);
- /**
- * Destructor
- */
~Loiter();
- /**
- * This function is called while the mode is inactive
- */
virtual void on_inactive();
- /**
- * This function is called while the mode is active
- */
- virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+ virtual void on_activation();
+
+ virtual void on_active();
};
#endif
diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp
index 72255103b..d39ca6cf9 100644
--- a/src/modules/navigator/mission.cpp
+++ b/src/modules/navigator/mission.cpp
@@ -54,25 +54,28 @@
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
-#include "navigator.h"
#include "mission.h"
+#include "navigator.h"
Mission::Mission(Navigator *navigator, const char *name) :
MissionBlock(navigator, name),
_param_onboard_enabled(this, "ONBOARD_EN"),
+ _param_takeoff_alt(this, "TAKEOFF_ALT"),
_onboard_mission({0}),
_offboard_mission({0}),
_current_onboard_mission_index(-1),
_current_offboard_mission_index(-1),
+ _need_takeoff(true),
+ _takeoff(false),
_mission_result_pub(-1),
_mission_result({0}),
_mission_type(MISSION_TYPE_NONE)
{
/* load initial params */
updateParams();
+
/* set initial mission items */
on_inactive();
-
}
Mission::~Mission()
@@ -82,8 +85,6 @@ Mission::~Mission()
void
Mission::on_inactive()
{
- _first_run = true;
-
/* check anyway if missions have changed so that feedback to groundstation is given */
bool onboard_updated;
orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
@@ -96,13 +97,21 @@ Mission::on_inactive()
if (offboard_updated) {
update_offboard_mission();
}
+
+ if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) {
+ _need_takeoff = true;
+ }
}
-bool
-Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+void
+Mission::on_activation()
{
- bool updated = false;
+ set_mission_items();
+}
+void
+Mission::on_active()
+{
/* check if anything has changed */
bool onboard_updated;
orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated);
@@ -117,20 +126,21 @@ Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
}
/* reset mission items if needed */
- if (onboard_updated || offboard_updated || _first_run) {
- set_mission_items(pos_sp_triplet);
- updated = true;
- _first_run = false;
+ if (onboard_updated || offboard_updated) {
+ set_mission_items();
}
/* lets check if we reached the current mission item */
if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) {
advance_mission();
- set_mission_items(pos_sp_triplet);
- updated = true;
- }
+ set_mission_items();
- return updated;
+ } else {
+ /* if waypoint position reached allow loiter on the setpoint */
+ if (_waypoint_position_reached && _mission_item.nav_cmd != NAV_CMD_IDLE) {
+ _navigator->set_can_loiter_at_sp(true);
+ }
+ }
}
void
@@ -151,6 +161,7 @@ Mission::update_onboard_mission()
}
/* otherwise, just leave it */
}
+
} else {
_onboard_mission.count = 0;
_onboard_mission.current_index = 0;
@@ -167,10 +178,12 @@ Mission::update_offboard_mission()
if (_offboard_mission.current_index >= 0
&& _offboard_mission.current_index < (int)_offboard_mission.count) {
_current_offboard_mission_index = _offboard_mission.current_index;
+
} else {
/* if less WPs available, reset to first WP */
if (_current_offboard_mission_index >= (int)_offboard_mission.count) {
_current_offboard_mission_index = 0;
+
/* if not initialized, set it to 0 */
} else if (_current_offboard_mission_index < 0) {
_current_offboard_mission_index = 0;
@@ -184,6 +197,7 @@ Mission::update_offboard_mission()
if (_offboard_mission.dataman_id == 0) {
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+
} else {
dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
@@ -192,11 +206,13 @@ Mission::update_offboard_mission()
(size_t)_offboard_mission.count,
_navigator->get_geofence(),
_navigator->get_home_position()->alt);
+
} else {
_offboard_mission.count = 0;
_offboard_mission.current_index = 0;
_current_offboard_mission_index = 0;
}
+
report_current_offboard_mission_item();
}
@@ -204,46 +220,55 @@ Mission::update_offboard_mission()
void
Mission::advance_mission()
{
- switch (_mission_type) {
- case MISSION_TYPE_ONBOARD:
- _current_onboard_mission_index++;
- break;
-
- case MISSION_TYPE_OFFBOARD:
- _current_offboard_mission_index++;
- break;
-
- case MISSION_TYPE_NONE:
- default:
- break;
+ if (_takeoff) {
+ _takeoff = false;
+
+ } else {
+ switch (_mission_type) {
+ case MISSION_TYPE_ONBOARD:
+ _current_onboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_OFFBOARD:
+ _current_offboard_mission_index++;
+ break;
+
+ case MISSION_TYPE_NONE:
+ default:
+ break;
+ }
}
}
void
-Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet)
+Mission::set_mission_items()
{
- set_previous_pos_setpoint(pos_sp_triplet);
+ /* make sure param is up to date */
+ updateParams();
+
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ /* set previous position setpoint to current */
+ set_previous_pos_setpoint();
/* try setting onboard mission item */
- if (is_current_onboard_mission_item_set(&pos_sp_triplet->current)) {
+ if (_param_onboard_enabled.get() && read_mission_item(true, true, &_mission_item)) {
/* if mission type changed, notify */
if (_mission_type != MISSION_TYPE_ONBOARD) {
- mavlink_log_info(_navigator->get_mavlink_fd(),
- "#audio: onboard mission running");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running");
}
_mission_type = MISSION_TYPE_ONBOARD;
- _navigator->set_can_loiter_at_sp(false);
/* try setting offboard mission item */
- } else if (is_current_offboard_mission_item_set(&pos_sp_triplet->current)) {
+ } else if (read_mission_item(false, true, &_mission_item)) {
/* if mission type changed, notify */
if (_mission_type != MISSION_TYPE_OFFBOARD) {
- mavlink_log_info(_navigator->get_mavlink_fd(),
- "#audio: offboard mission running");
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running");
}
_mission_type = MISSION_TYPE_OFFBOARD;
- _navigator->set_can_loiter_at_sp(false);
+
} else {
+ /* no mission available, switch to loiter */
if (_mission_type != MISSION_TYPE_NONE) {
mavlink_log_info(_navigator->get_mavlink_fd(),
"#audio: mission finished");
@@ -252,125 +277,152 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet)
"#audio: no mission available");
}
_mission_type = MISSION_TYPE_NONE;
- _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached);
- set_loiter_item(pos_sp_triplet);
+ /* set loiter mission item */
+ set_loiter_item(&_mission_item);
+
+ /* update position setpoint triplet */
+ pos_sp_triplet->previous.valid = false;
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+ pos_sp_triplet->next.valid = false;
+
+ _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER);
+
reset_mission_item_reached();
report_mission_finished();
+
+ _navigator->set_position_setpoint_triplet_updated();
+ return;
}
-}
-bool
-Mission::is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
-{
- /* make sure param is up to date */
- updateParams();
- if (_param_onboard_enabled.get() > 0 &&
- _current_onboard_mission_index >= 0&&
- _current_onboard_mission_index < (int)_onboard_mission.count) {
- struct mission_item_s new_mission_item;
- if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, true, &_current_onboard_mission_index,
- &new_mission_item)) {
- /* convert the current mission item and set it valid */
- mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
- current_pos_sp->valid = true;
-
- reset_mission_item_reached();
-
- /* TODO: report this somehow */
- memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
- return true;
+ /* do takeoff on first waypoint for rotary wing vehicles */
+ if (_navigator->get_vstatus()->is_rotary_wing) {
+ /* force takeoff if landed (additional protection) */
+ if (!_takeoff && _navigator->get_vstatus()->condition_landed) {
+ _need_takeoff = true;
+ }
+
+ /* new current mission item set, check if we need takeoff */
+ if (_need_takeoff && (
+ _mission_item.nav_cmd == NAV_CMD_TAKEOFF ||
+ _mission_item.nav_cmd == NAV_CMD_WAYPOINT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT ||
+ _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED ||
+ _mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH)) {
+ _takeoff = true;
+ _need_takeoff = false;
}
}
- return false;
-}
-bool
-Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp)
-{
- if (_current_offboard_mission_index >= 0 &&
- _current_offboard_mission_index < (int)_offboard_mission.count) {
- dm_item_t dm_current;
- if (_offboard_mission.dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ if (_takeoff) {
+ /* do takeoff before going to setpoint */
+ /* set mission item as next position setpoint */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->next);
+
+ /* calculate takeoff altitude */
+ float takeoff_alt = _mission_item.altitude;
+ if (_mission_item.altitude_is_relative) {
+ takeoff_alt += _navigator->get_home_position()->alt;
+ }
+
+ /* perform takeoff at least to NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */
+ if (_navigator->get_vstatus()->condition_landed) {
+ takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get());
+
} else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
+ takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get());
+ }
+
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", (double)(takeoff_alt - _navigator->get_home_position()->alt));
+
+ _mission_item.lat = _navigator->get_global_position()->lat;
+ _mission_item.lon = _navigator->get_global_position()->lon;
+ _mission_item.altitude = takeoff_alt;
+ _mission_item.altitude_is_relative = false;
+
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+
+ } else {
+ /* set current position setpoint from mission item */
+ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
+
+ /* require takeoff after landing or idle */
+ if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) {
+ _need_takeoff = true;
}
- struct mission_item_s new_mission_item;
- if (read_mission_item(dm_current, true, &_current_offboard_mission_index, &new_mission_item)) {
- /* convert the current mission item and set it valid */
- mission_item_to_position_setpoint(&new_mission_item, current_pos_sp);
- current_pos_sp->valid = true;
- reset_mission_item_reached();
+ _navigator->set_can_loiter_at_sp(false);
+ reset_mission_item_reached();
+ if (_mission_type == MISSION_TYPE_OFFBOARD) {
report_current_offboard_mission_item();
- memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s));
- return true;
}
- }
- return false;
-}
+ // TODO: report onboard mission item somehow
-void
-Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp)
-{
- int next_temp_mission_index = _onboard_mission.current_index + 1;
-
- /* try if there is a next onboard mission */
- if (_onboard_mission.current_index >= 0 &&
- next_temp_mission_index < (int)_onboard_mission.count) {
- struct mission_item_s new_mission_item;
- if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) {
- /* convert next mission item to position setpoint */
- mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
- next_pos_sp->valid = true;
- return;
+ /* try to read next mission item */
+ struct mission_item_s mission_item_next;
+
+ if (read_mission_item(_mission_type == MISSION_TYPE_ONBOARD, false, &mission_item_next)) {
+ /* got next mission item, update setpoint triplet */
+ mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next);
+
+ } else {
+ /* next mission item is not available */
+ pos_sp_triplet->next.valid = false;
}
}
- /* give up */
- next_pos_sp->valid = false;
- return;
+ _navigator->set_position_setpoint_triplet_updated();
}
-void
-Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp)
+bool
+Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item)
{
- /* try if there is a next offboard mission */
- int next_temp_mission_index = _offboard_mission.current_index + 1;
- warnx("next index: %d, count; %d", next_temp_mission_index, _offboard_mission.count);
- if (_offboard_mission.current_index >= 0 &&
- next_temp_mission_index < (int)_offboard_mission.count) {
- dm_item_t dm_current;
+ /* select onboard/offboard mission */
+ int *mission_index_ptr;
+ struct mission_s *mission;
+ dm_item_t dm_item;
+ int mission_index_next;
+
+ if (onboard) {
+ /* onboard mission */
+ mission_index_next = _current_onboard_mission_index + 1;
+ mission_index_ptr = is_current ? &_current_onboard_mission_index : &mission_index_next;
+
+ mission = &_onboard_mission;
+
+ dm_item = DM_KEY_WAYPOINTS_ONBOARD;
+
+ } else {
+ /* offboard mission */
+ mission_index_next = _current_offboard_mission_index + 1;
+ mission_index_ptr = is_current ? &_current_offboard_mission_index : &mission_index_next;
+
+ mission = &_offboard_mission;
+
if (_offboard_mission.dataman_id == 0) {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0;
+ dm_item = DM_KEY_WAYPOINTS_OFFBOARD_0;
+
} else {
- dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1;
- }
- struct mission_item_s new_mission_item;
- if (read_mission_item(dm_current, false, &next_temp_mission_index, &new_mission_item)) {
- /* convert next mission item to position setpoint */
- mission_item_to_position_setpoint(&new_mission_item, next_pos_sp);
- next_pos_sp->valid = true;
- return;
+ dm_item = DM_KEY_WAYPOINTS_OFFBOARD_1;
}
}
- /* give up */
- next_pos_sp->valid = false;
- return;
-}
-bool
-Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index,
- struct mission_item_s *new_mission_item)
-{
+ if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) {
+ /* mission item index out of bounds */
+ return false;
+ }
+
/* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */
- for (int i=0; i<10; i++) {
+ for (int i = 0; i < 10; i++) {
const ssize_t len = sizeof(struct mission_item_s);
+ /* read mission item to temp storage first to not overwrite current mission item if data damaged */
+ struct mission_item_s mission_item_tmp;
+
/* read mission item from datamanager */
- if (dm_read(dm_item, *mission_index, new_mission_item, len) != len) {
+ if (dm_read(dm_item, *mission_index_ptr, &mission_item_tmp, len) != len) {
/* not supposed to happen unless the datamanager can't access the SD card, etc. */
mavlink_log_critical(_navigator->get_mavlink_fd(),
"#audio: ERROR waypoint could not be read");
@@ -378,18 +430,17 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio
}
/* check for DO_JUMP item, and whether it hasn't not already been repeated enough times */
- if (new_mission_item->nav_cmd == NAV_CMD_DO_JUMP) {
+ if (mission_item_tmp.nav_cmd == NAV_CMD_DO_JUMP) {
/* do DO_JUMP as many times as requested */
- if (new_mission_item->do_jump_current_count < new_mission_item->do_jump_repeat_count) {
+ if (mission_item_tmp.do_jump_current_count < mission_item_tmp.do_jump_repeat_count) {
/* only raise the repeat count if this is for the current mission item
* but not for the next mission item */
if (is_current) {
- (new_mission_item->do_jump_current_count)++;
+ (mission_item_tmp.do_jump_current_count)++;
/* save repeat count */
- if (dm_write(dm_item, *mission_index, DM_PERSIST_IN_FLIGHT_RESET,
- new_mission_item, len) != len) {
+ if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, &mission_item_tmp, len) != len) {
/* not supposed to happen unless the datamanager can't access the
* dataman */
mavlink_log_critical(_navigator->get_mavlink_fd(),
@@ -399,16 +450,18 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio
}
/* set new mission item index and repeat
* we don't have to validate here, if it's invalid, we should realize this later .*/
- *mission_index = new_mission_item->do_jump_mission_index;
+ *mission_index_ptr = mission_item_tmp.do_jump_mission_index;
+
} else {
mavlink_log_info(_navigator->get_mavlink_fd(),
"#audio: DO JUMP repetitions completed");
/* no more DO_JUMPS, therefore just try to continue with next mission item */
- (*mission_index)++;
+ (*mission_index_ptr)++;
}
} else {
/* if it's not a DO_JUMP, then we were successful */
+ memcpy(mission_item, &mission_item_tmp, sizeof(struct mission_item_s));
return true;
}
}
diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h
index 6e4761946..d4808b6f4 100644
--- a/src/modules/navigator/mission.h
+++ b/src/modules/navigator/mission.h
@@ -65,25 +65,15 @@ class Navigator;
class Mission : public MissionBlock
{
public:
- /**
- * Constructor
- */
Mission(Navigator *navigator, const char *name);
- /**
- * Destructor
- */
virtual ~Mission();
- /**
- * This function is called while the mode is inactive
- */
virtual void on_inactive();
- /**
- * This function is called while the mode is active
- */
- virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+ virtual void on_activation();
+
+ virtual void on_active();
private:
/**
@@ -104,36 +94,13 @@ private:
/**
* Set new mission items
*/
- void set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet);
-
- /**
- * Try to set the current position setpoint from an onboard mission item
- * @return true if mission item successfully set
- */
- bool is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp);
-
- /**
- * Try to set the current position setpoint from an offboard mission item
- * @return true if mission item successfully set
- */
- bool is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp);
-
- /**
- * Try to set the next position setpoint from an onboard mission item
- */
- void get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp);
-
- /**
- * Try to set the next position setpoint from an offboard mission item
- */
- void get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp);
+ void set_mission_items();
/**
- * Read a mission item from the dataman and watch out for DO_JUMPS
+ * Read current or next mission item from the dataman and watch out for DO_JUMPS
* @return true if successful
*/
- bool read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index,
- struct mission_item_s *new_mission_item);
+ bool read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item);
/**
* Report that a mission item has been reached
@@ -156,12 +123,15 @@ private:
void publish_mission_result();
control::BlockParamFloat _param_onboard_enabled;
+ control::BlockParamFloat _param_takeoff_alt;
struct mission_s _onboard_mission;
struct mission_s _offboard_mission;
int _current_onboard_mission_index;
int _current_offboard_mission_index;
+ bool _need_takeoff;
+ bool _takeoff;
orb_advert_t _mission_result_pub;
struct mission_result_s _mission_result;
diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp
index 26a573544..4adf77dce 100644
--- a/src/modules/navigator/mission_block.cpp
+++ b/src/modules/navigator/mission_block.cpp
@@ -47,6 +47,7 @@
#include <systemlib/err.h>
#include <geo/geo.h>
+#include <mavlink/mavlink_log.h>
#include <uORB/uORB.h>
@@ -56,11 +57,10 @@
MissionBlock::MissionBlock(Navigator *navigator, const char *name) :
NavigatorMode(navigator, name),
+ _mission_item({0}),
_waypoint_position_reached(false),
_waypoint_yaw_reached(false),
- _time_first_inside_orbit(0),
- _mission_item({0}),
- _mission_item_valid(false)
+ _time_first_inside_orbit(0)
{
}
@@ -71,6 +71,10 @@ MissionBlock::~MissionBlock()
bool
MissionBlock::is_mission_item_reached()
{
+ if (_mission_item.nav_cmd == NAV_CMD_IDLE) {
+ return false;
+ }
+
if (_mission_item.nav_cmd == NAV_CMD_LAND) {
return _navigator->get_vstatus()->condition_landed;
}
@@ -84,7 +88,6 @@ MissionBlock::is_mission_item_reached()
hrt_abstime now = hrt_absolute_time();
if (!_waypoint_position_reached) {
-
float dist = -1.0f;
float dist_xy = -1.0f;
float dist_z = -1.0f;
@@ -201,44 +204,48 @@ MissionBlock::mission_item_to_position_setpoint(const struct mission_item_s *ite
}
void
-MissionBlock::set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet)
+MissionBlock::set_previous_pos_setpoint()
{
- /* reuse current setpoint as previous setpoint */
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
if (pos_sp_triplet->current.valid) {
memcpy(&pos_sp_triplet->previous, &pos_sp_triplet->current, sizeof(struct position_setpoint_s));
}
}
-bool
-MissionBlock::set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet)
+void
+MissionBlock::set_loiter_item(struct mission_item_s *item)
{
- /* don't change setpoint if 'can_loiter_at_sp' flag set */
- if (!(_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid)) {
- /* use current position */
- pos_sp_triplet->current.lat = _navigator->get_global_position()->lat;
- pos_sp_triplet->current.lon = _navigator->get_global_position()->lon;
- pos_sp_triplet->current.alt = _navigator->get_global_position()->alt;
- pos_sp_triplet->current.yaw = NAN; /* NAN means to use current yaw */
-
- _navigator->set_can_loiter_at_sp(true);
- }
+ if (_navigator->get_vstatus()->condition_landed) {
+ /* landed, don't takeoff, but switch to IDLE mode */
+ item->nav_cmd = NAV_CMD_IDLE;
- if (pos_sp_triplet->current.type != SETPOINT_TYPE_LOITER
- || (fabsf(pos_sp_triplet->current.loiter_radius - _navigator->get_loiter_radius()) > FLT_EPSILON)
- || pos_sp_triplet->current.loiter_direction != 1
- || pos_sp_triplet->previous.valid
- || !pos_sp_triplet->current.valid
- || pos_sp_triplet->next.valid) {
- /* position setpoint triplet should be updated */
- pos_sp_triplet->current.type = SETPOINT_TYPE_LOITER;
- pos_sp_triplet->current.loiter_radius = _navigator->get_loiter_radius();
- pos_sp_triplet->current.loiter_direction = 1;
-
- pos_sp_triplet->previous.valid = false;
- pos_sp_triplet->current.valid = true;
- pos_sp_triplet->next.valid = false;
- return true;
- }
+ } else {
+ item->nav_cmd = NAV_CMD_LOITER_UNLIMITED;
+
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ if (_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid) {
+ /* use current position setpoint */
+ item->lat = pos_sp_triplet->current.lat;
+ item->lon = pos_sp_triplet->current.lon;
+ item->altitude = pos_sp_triplet->current.alt;
- return false;
+ } else {
+ /* use current position */
+ item->lat = _navigator->get_global_position()->lat;
+ item->lon = _navigator->get_global_position()->lon;
+ item->altitude = _navigator->get_global_position()->alt;
+ }
+
+ item->altitude_is_relative = false;
+ item->yaw = NAN;
+ item->loiter_radius = _navigator->get_loiter_radius();
+ item->loiter_direction = 1;
+ item->acceptance_radius = _navigator->get_acceptance_radius();
+ item->time_inside = 0.0f;
+ item->pitch_min = 0.0f;
+ item->autocontinue = false;
+ item->origin = ORIGIN_ONBOARD;
+ }
}
diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h
index f99002752..adf50bc39 100644
--- a/src/modules/navigator/mission_block.h
+++ b/src/modules/navigator/mission_block.h
@@ -64,6 +64,7 @@ public:
*/
virtual ~MissionBlock();
+protected:
/**
* Check if mission item has been reached
* @return true if successfully reached
@@ -85,22 +86,17 @@ public:
/**
* Set previous position setpoint to current setpoint
*/
- void set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet);
+ void set_previous_pos_setpoint();
/**
- * Set a loiter item, if possible reuse the position setpoint, otherwise take the current position
- *
- * @param the position setpoint triplet to set
- * @return true if setpoint has changed
+ * Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position
*/
- bool set_loiter_item(position_setpoint_triplet_s *pos_sp_triplet);
+ void set_loiter_item(struct mission_item_s *item);
+ mission_item_s _mission_item;
bool _waypoint_position_reached;
bool _waypoint_yaw_reached;
hrt_abstime _time_first_inside_orbit;
-
- mission_item_s _mission_item;
- bool _mission_item_valid;
};
#endif
diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk
index a1e109030..637eaae59 100644
--- a/src/modules/navigator/module.mk
+++ b/src/modules/navigator/module.mk
@@ -46,6 +46,7 @@ SRCS = navigator_main.cpp \
loiter.cpp \
rtl.cpp \
rtl_params.c \
+ offboard.cpp \
mission_feasibility_checker.cpp \
geofence.cpp \
geofence_params.c
diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h
index 184ecd365..bf6e2ea0e 100644
--- a/src/modules/navigator/navigator.h
+++ b/src/modules/navigator/navigator.h
@@ -56,13 +56,14 @@
#include "mission.h"
#include "loiter.h"
#include "rtl.h"
+#include "offboard.h"
#include "geofence.h"
/**
* Number of navigation modes that need on_active/on_inactive calls
* Currently: mission, loiter, and rtl
*/
-#define NAVIGATOR_MODE_ARRAY_SIZE 3
+#define NAVIGATOR_MODE_ARRAY_SIZE 4
class Navigator : public control::SuperBlock
{
@@ -103,15 +104,19 @@ public:
* Setters
*/
void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; }
+ void set_position_setpoint_triplet_updated() { _pos_sp_triplet_updated = true; }
/**
* Getters
*/
struct vehicle_status_s* get_vstatus() { return &_vstatus; }
+ struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; }
struct vehicle_global_position_s* get_global_position() { return &_global_pos; }
struct home_position_s* get_home_position() { return &_home_pos; }
+ struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; }
int get_onboard_mission_sub() { return _onboard_mission_sub; }
int get_offboard_mission_sub() { return _offboard_mission_sub; }
+ int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; }
Geofence& get_geofence() { return _geofence; }
bool get_can_loiter_at_sp() { return _can_loiter_at_sp; }
float get_loiter_radius() { return _param_loiter_radius.get(); }
@@ -129,6 +134,7 @@ private:
int _home_pos_sub; /**< home position subscription */
int _vstatus_sub; /**< vehicle status subscription */
int _capabilities_sub; /**< notification of vehicle capabilities updates */
+ int _offboard_control_sp_sub; /*** offboard control subscription */
int _control_mode_sub; /**< vehicle control mode subscription */
int _onboard_mission_sub; /**< onboard mission subscription */
int _offboard_mission_sub; /**< offboard mission subscription */
@@ -158,11 +164,12 @@ private:
Mission _mission; /**< class that handles the missions */
Loiter _loiter; /**< class that handles loiter */
RTL _rtl; /**< class that handles RTL */
+ Offboard _offboard; /**< class that handles offboard */
NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */
bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */
- bool _update_triplet; /**< flags if position SP triplet needs to be published */
+ bool _pos_sp_triplet_updated; /**< flags if position SP triplet needs to be published */
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp
index 546602741..1a5ba4c1a 100644
--- a/src/modules/navigator/navigator_main.cpp
+++ b/src/modules/navigator/navigator_main.cpp
@@ -67,6 +67,7 @@
#include <uORB/topics/mission.h>
#include <uORB/topics/fence.h>
#include <uORB/topics/navigation_capabilities.h>
+#include <uORB/topics/offboard_control_setpoint.h>
#include <systemlib/err.h>
#include <systemlib/systemlib.h>
@@ -100,6 +101,7 @@ Navigator::Navigator() :
_home_pos_sub(-1),
_vstatus_sub(-1),
_capabilities_sub(-1),
+ _offboard_control_sp_sub(-1),
_control_mode_sub(-1),
_onboard_mission_sub(-1),
_offboard_mission_sub(-1),
@@ -121,7 +123,7 @@ Navigator::Navigator() :
_mission(this, "MIS"),
_loiter(this, "LOI"),
_rtl(this, "RTL"),
- _update_triplet(false),
+ _offboard(this, "OFF"),
_param_loiter_radius(this, "LOITER_RAD"),
_param_acceptance_radius(this, "ACC_RAD")
{
@@ -129,6 +131,7 @@ Navigator::Navigator() :
_navigation_mode_array[0] = &_mission;
_navigation_mode_array[1] = &_loiter;
_navigation_mode_array[2] = &_rtl;
+ _navigation_mode_array[3] = &_offboard;
updateParams();
}
@@ -241,6 +244,7 @@ Navigator::task_main()
_onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission));
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
_param_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ _offboard_control_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint));
/* copy all topics first time */
vehicle_status_update();
@@ -363,6 +367,9 @@ Navigator::task_main()
break;
case NAVIGATION_STATE_LAND:
case NAVIGATION_STATE_TERMINATION:
+ case NAVIGATION_STATE_OFFBOARD:
+ _navigation_mode = &_offboard;
+ break;
default:
_navigation_mode = nullptr;
_can_loiter_at_sp = false;
@@ -371,24 +378,21 @@ Navigator::task_main()
/* iterate through navigation modes and set active/inactive for each */
for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) {
- if (_navigation_mode == _navigation_mode_array[i]) {
- _update_triplet = _navigation_mode_array[i]->on_active(&_pos_sp_triplet);
- } else {
- _navigation_mode_array[i]->on_inactive();
- }
+ _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);
}
/* if nothing is running, set position setpoint triplet invalid */
if (_navigation_mode == nullptr) {
+ // TODO publish empty sp only once
_pos_sp_triplet.previous.valid = false;
_pos_sp_triplet.current.valid = false;
_pos_sp_triplet.next.valid = false;
- _update_triplet = true;
+ _pos_sp_triplet_updated = true;
}
- if (_update_triplet) {
+ if (_pos_sp_triplet_updated) {
publish_position_setpoint_triplet();
- _update_triplet = false;
+ _pos_sp_triplet_updated = false;
}
perf_end(_loop_perf);
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
index 25e767c2b..f43215665 100644
--- a/src/modules/navigator/navigator_mode.cpp
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -33,12 +33,14 @@
/**
* @file navigator_mode.cpp
*
- * Helper class for different modes in navigator
+ * Base class for different modes in navigator
*
* @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#include "navigator_mode.h"
+#include "navigator.h"
NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) :
SuperBlock(NULL, name),
@@ -56,15 +58,38 @@ NavigatorMode::~NavigatorMode()
}
void
+NavigatorMode::run(bool active) {
+ if (active) {
+ if (_first_run) {
+ /* first run */
+ _first_run = false;
+ on_activation();
+
+ } else {
+ /* periodic updates when active */
+ on_active();
+ }
+
+ } else {
+ /* periodic updates when inactive */
+ _first_run = true;
+ on_inactive();
+ }
+}
+
+void
NavigatorMode::on_inactive()
{
- _first_run = true;
}
-bool
-NavigatorMode::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+void
+NavigatorMode::on_activation()
+{
+ /* invalidate position setpoint by default */
+ _navigator->get_position_setpoint_triplet()->current.valid = false;
+}
+
+void
+NavigatorMode::on_active()
{
- pos_sp_triplet->current.valid = false;
- _first_run = false;
- return false;
}
diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h
index cbb53d91b..a7ba79bba 100644
--- a/src/modules/navigator/navigator_mode.h
+++ b/src/modules/navigator/navigator_mode.h
@@ -33,9 +33,10 @@
/**
* @file navigator_mode.h
*
- * Helper class for different modes in navigator
+ * Base class for different modes in navigator
*
* @author Julian Oes <julian@oes.ch>
+ * @author Anton Babushkin <anton.babushkin@me.com>
*/
#ifndef NAVIGATOR_MODE_H
@@ -65,21 +66,27 @@ public:
*/
virtual ~NavigatorMode();
+ void run(bool active);
+
/**
* This function is called while the mode is inactive
*/
virtual void on_inactive();
/**
+ * This function is called one time when mode become active, poos_sp_triplet must be initialized here
+ */
+ virtual void on_activation();
+
+ /**
* This function is called while the mode is active
- *
- * @param position setpoint triplet to set
- * @return true if position setpoint triplet has been changed
*/
- virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet);
+ virtual void on_active();
protected:
Navigator *_navigator;
+
+private:
bool _first_run;
};
diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp
new file mode 100644
index 000000000..dcb5c6000
--- /dev/null
+++ b/src/modules/navigator/offboard.cpp
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file offboard.cpp
+ *
+ * Helper class for offboard commands
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#include <string.h>
+#include <stdlib.h>
+#include <stdbool.h>
+#include <math.h>
+#include <fcntl.h>
+
+#include <mavlink/mavlink_log.h>
+#include <systemlib/err.h>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/position_setpoint_triplet.h>
+
+#include "navigator.h"
+#include "offboard.h"
+
+Offboard::Offboard(Navigator *navigator, const char *name) :
+ NavigatorMode(navigator, name),
+ _offboard_control_sp({0})
+{
+ /* load initial params */
+ updateParams();
+ /* initial reset */
+ on_inactive();
+}
+
+Offboard::~Offboard()
+{
+}
+
+void
+Offboard::on_inactive()
+{
+}
+
+void
+Offboard::on_activation()
+{
+}
+
+void
+Offboard::on_active()
+{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
+ bool updated;
+ orb_check(_navigator->get_offboard_control_sp_sub(), &updated);
+ if (updated) {
+ update_offboard_control_setpoint();
+ }
+
+ /* copy offboard setpoints to the corresponding topics */
+ if (_navigator->get_control_mode()->flag_control_position_enabled
+ && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) {
+ /* position control */
+ pos_sp_triplet->current.x = _offboard_control_sp.p1;
+ pos_sp_triplet->current.y = _offboard_control_sp.p2;
+ pos_sp_triplet->current.yaw = _offboard_control_sp.p3;
+ pos_sp_triplet->current.z = -_offboard_control_sp.p4;
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.position_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+
+ } else if (_navigator->get_control_mode()->flag_control_velocity_enabled
+ && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) {
+ /* velocity control */
+ pos_sp_triplet->current.vx = _offboard_control_sp.p2;
+ pos_sp_triplet->current.vy = _offboard_control_sp.p1;
+ pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3;
+ pos_sp_triplet->current.vz = _offboard_control_sp.p4;
+
+ pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD;
+ pos_sp_triplet->current.valid = true;
+ pos_sp_triplet->current.velocity_valid = true;
+
+ _navigator->set_position_setpoint_triplet_updated();
+ }
+
+}
+
+
+void
+Offboard::update_offboard_control_setpoint()
+{
+ orb_copy(ORB_ID(offboard_control_setpoint), _navigator->get_offboard_control_sp_sub(), &_offboard_control_sp);
+
+}
diff --git a/src/modules/navigator/offboard.h b/src/modules/navigator/offboard.h
new file mode 100644
index 000000000..66b923bdb
--- /dev/null
+++ b/src/modules/navigator/offboard.h
@@ -0,0 +1,72 @@
+/***************************************************************************
+ *
+ * Copyright (c) 2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/**
+ * @file offboard.h
+ *
+ * Helper class for offboard commands
+ *
+ * @author Julian Oes <julian@oes.ch>
+ */
+
+#ifndef NAVIGATOR_OFFBOARD_H
+#define NAVIGATOR_OFFBOARD_H
+
+#include <controllib/blocks.hpp>
+#include <controllib/block/BlockParam.hpp>
+
+#include <uORB/uORB.h>
+#include <uORB/topics/offboard_control_setpoint.h>
+
+#include "navigator_mode.h"
+
+class Navigator;
+
+class Offboard : public NavigatorMode
+{
+public:
+ Offboard(Navigator *navigator, const char *name);
+
+ ~Offboard();
+
+ virtual void on_inactive();
+
+ virtual void on_activation();
+
+ virtual void on_active();
+private:
+ void update_offboard_control_setpoint();
+
+ struct offboard_control_setpoint_s _offboard_control_sp;
+};
+
+#endif
diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp
index 597a2c0ec..142a73409 100644
--- a/src/modules/navigator/rtl.cpp
+++ b/src/modules/navigator/rtl.cpp
@@ -75,62 +75,57 @@ RTL::~RTL()
void
RTL::on_inactive()
{
- _first_run = true;
-
/* reset RTL state only if setpoint moved */
if (!_navigator->get_can_loiter_at_sp()) {
_rtl_state = RTL_STATE_NONE;
}
}
-bool
-RTL::on_active(struct position_setpoint_triplet_s *pos_sp_triplet)
+void
+RTL::on_activation()
{
- bool updated = false;
-
- if (_first_run) {
- _first_run = false;
-
- /* decide where to enter the RTL procedure when we switch into it */
- if (_rtl_state == RTL_STATE_NONE) {
- /* for safety reasons don't go into RTL if landed */
- if (_navigator->get_vstatus()->condition_landed) {
- _rtl_state = RTL_STATE_LANDED;
- mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed");
-
- /* if lower than return altitude, climb up first */
- } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt
- + _param_return_alt.get()) {
- _rtl_state = RTL_STATE_CLIMB;
-
- /* otherwise go straight to return */
- } else {
- /* set altitude setpoint to current altitude */
- _rtl_state = RTL_STATE_RETURN;
- _mission_item.altitude_is_relative = false;
- _mission_item.altitude = _navigator->get_global_position()->alt;
- }
+ /* decide where to enter the RTL procedure when we switch into it */
+ if (_rtl_state == RTL_STATE_NONE) {
+ /* for safety reasons don't go into RTL if landed */
+ if (_navigator->get_vstatus()->condition_landed) {
+ _rtl_state = RTL_STATE_LANDED;
+ mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed");
+
+ /* if lower than return altitude, climb up first */
+ } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt
+ + _param_return_alt.get()) {
+ _rtl_state = RTL_STATE_CLIMB;
+
+ /* otherwise go straight to return */
+ } else {
+ /* set altitude setpoint to current altitude */
+ _rtl_state = RTL_STATE_RETURN;
+ _mission_item.altitude_is_relative = false;
+ _mission_item.altitude = _navigator->get_global_position()->alt;
}
+ }
- set_rtl_item(pos_sp_triplet);
- updated = true;
+ set_rtl_item();
+}
- } else if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) {
+void
+RTL::on_active()
+{
+ if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) {
advance_rtl();
- set_rtl_item(pos_sp_triplet);
- updated = true;
+ set_rtl_item();
}
-
- return updated;
}
void
-RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
+RTL::set_rtl_item()
{
+ struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet();
+
/* make sure we have the latest params */
updateParams();
- set_previous_pos_setpoint(pos_sp_triplet);
+ set_previous_pos_setpoint();
_navigator->set_can_loiter_at_sp(false);
switch (_rtl_state) {
@@ -277,11 +272,13 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
break;
}
+ reset_mission_item_reached();
+
/* convert mission item to current position setpoint and make it valid */
mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current);
- reset_mission_item_reached();
- pos_sp_triplet->current.valid = true;
pos_sp_triplet->next.valid = false;
+
+ _navigator->set_position_setpoint_triplet_updated();
}
void
diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h
index b4b729e89..5928f1f07 100644
--- a/src/modules/navigator/rtl.h
+++ b/src/modules/navigator/rtl.h
@@ -57,35 +57,21 @@ class Navigator;
class RTL : public MissionBlock
{
public:
- /**
- * Constructor
- */
RTL(Navigator *navigator, const char *name);
- /**
- * Destructor
- */
~RTL();
- /**
- * This function is called while the mode is inactive
- */
- void on_inactive();
+ virtual void on_inactive();
- /**
- * This function is called while the mode is active
- *
- * @param position setpoint triplet that needs to be set
- * @return true if updated
- */
- bool on_active(position_setpoint_triplet_s *pos_sp_triplet);
+ virtual void on_activation();
+ virtual void on_active();
private:
/**
* Set the RTL item
*/
- void set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet);
+ void set_rtl_item();
/**
* Move to next RTL item
diff --git a/src/modules/px4iofirmware/i2c.c b/src/modules/px4iofirmware/i2c.c
index 76762c0fc..6d1d1fc2d 100644
--- a/src/modules/px4iofirmware/i2c.c
+++ b/src/modules/px4iofirmware/i2c.c
@@ -64,12 +64,15 @@
#define rCCR REG(STM32_I2C_CCR_OFFSET)
#define rTRISE REG(STM32_I2C_TRISE_OFFSET)
+void i2c_reset(void);
static int i2c_interrupt(int irq, void *context);
static void i2c_rx_setup(void);
static void i2c_tx_setup(void);
static void i2c_rx_complete(void);
static void i2c_tx_complete(void);
+#ifdef DEBUG
static void i2c_dump(void);
+#endif
static DMA_HANDLE rx_dma;
static DMA_HANDLE tx_dma;
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index ca175bfbc..b00a96717 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -219,8 +219,8 @@ extern bool dsm_input(uint16_t *values, uint16_t *num_values);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
-extern bool sbus1_output(uint16_t *values, uint16_t num_values);
-extern bool sbus2_output(uint16_t *values, uint16_t num_values);
+extern void sbus1_output(uint16_t *values, uint16_t num_values);
+extern void sbus2_output(uint16_t *values, uint16_t num_values);
/** global debug level for isr_debug() */
extern volatile uint8_t debug_level;
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 50108ea1b..b37259997 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -711,7 +711,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val
{
#define SELECT_PAGE(_page_name) \
do { \
- *values = &_page_name[0]; \
+ *values = (uint16_t *)&_page_name[0]; \
*num_values = sizeof(_page_name) / sizeof(_page_name[0]); \
} while(0)
diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c
index 70ccab180..0f0414148 100644
--- a/src/modules/px4iofirmware/sbus.c
+++ b/src/modules/px4iofirmware/sbus.c
@@ -116,14 +116,14 @@ sbus_init(const char *device)
return sbus_fd;
}
-bool
+void
sbus1_output(uint16_t *values, uint16_t num_values)
{
char a = 'A';
write(sbus_fd, &a, 1);
}
-bool
+void
sbus2_output(uint16_t *values, uint16_t num_values)
{
char b = 'B';
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 39e5b6c41..0d36fa2c6 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -979,7 +979,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_GVSP_s log_GVSP;
struct log_BATT_s log_BATT;
struct log_DIST_s log_DIST;
- struct log_TELE_s log_TELE;
+ struct log_TEL_s log_TEL;
struct log_EST0_s log_EST0;
struct log_EST1_s log_EST1;
struct log_PWR_s log_PWR;
@@ -1019,7 +1019,7 @@ int sdlog2_thread_main(int argc, char *argv[])
int esc_sub;
int global_vel_sp_sub;
int battery_sub;
- int telemetry_sub;
+ int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM];
int range_finder_sub;
int estimator_status_sub;
int tecs_status_sub;
@@ -1049,7 +1049,9 @@ int sdlog2_thread_main(int argc, char *argv[])
subs.esc_sub = orb_subscribe(ORB_ID(esc_status));
subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint));
subs.battery_sub = orb_subscribe(ORB_ID(battery_status));
- subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status));
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]);
+ }
subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder));
subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status));
subs.tecs_status_sub = orb_subscribe(ORB_ID(tecs_status));
@@ -1479,16 +1481,19 @@ int sdlog2_thread_main(int argc, char *argv[])
}
/* --- TELEMETRY --- */
- if (copy_if_updated(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry)) {
- log_msg.msg_type = LOG_TELE_MSG;
- log_msg.body.log_TELE.rssi = buf.telemetry.rssi;
- log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi;
- log_msg.body.log_TELE.noise = buf.telemetry.noise;
- log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise;
- log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors;
- log_msg.body.log_TELE.fixed = buf.telemetry.fixed;
- log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf;
- LOGBUFFER_WRITE_AND_COUNT(TELE);
+ for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) {
+ if (copy_if_updated(telemetry_status_orb_id[i], subs.telemetry_subs[i], &buf.telemetry)) {
+ log_msg.msg_type = LOG_TEL0_MSG + i;
+ log_msg.body.log_TEL.rssi = buf.telemetry.rssi;
+ log_msg.body.log_TEL.remote_rssi = buf.telemetry.remote_rssi;
+ log_msg.body.log_TEL.noise = buf.telemetry.noise;
+ log_msg.body.log_TEL.remote_noise = buf.telemetry.remote_noise;
+ log_msg.body.log_TEL.rxerrors = buf.telemetry.rxerrors;
+ log_msg.body.log_TEL.fixed = buf.telemetry.fixed;
+ log_msg.body.log_TEL.txbuf = buf.telemetry.txbuf;
+ log_msg.body.log_TEL.heartbeat_time = buf.telemetry.heartbeat_time;
+ LOGBUFFER_WRITE_AND_COUNT(TEL);
+ }
}
/* --- BOTTOM DISTANCE --- */
diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h
index dc5e6c8bd..aff0e3f48 100644
--- a/src/modules/sdlog2/sdlog2_format.h
+++ b/src/modules/sdlog2/sdlog2_format.h
@@ -91,6 +91,14 @@ struct log_format_s {
.labels = _labels \
}
+#define LOG_FORMAT_S(_name, _struct_name, _format, _labels) { \
+ .type = LOG_##_name##_MSG, \
+ .length = sizeof(struct log_##_struct_name##_s) + LOG_PACKET_HEADER_LEN, \
+ .name = #_name, \
+ .format = _format, \
+ .labels = _labels \
+ }
+
#define LOG_FORMAT_MSG 0x80
#define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s)
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 8c05e87c5..87f7f718f 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -276,18 +276,7 @@ struct log_DIST_s {
uint8_t flags;
};
-/* --- TELE - TELEMETRY STATUS --- */
-#define LOG_TELE_MSG 22
-struct log_TELE_s {
- uint8_t rssi;
- uint8_t remote_rssi;
- uint8_t noise;
- uint8_t remote_noise;
- uint16_t rxerrors;
- uint16_t fixed;
- uint8_t txbuf;
-};
-
+// ID 22 available
// ID 23 available
/* --- PWR - ONBOARD POWER SYSTEM --- */
@@ -385,6 +374,23 @@ struct log_EST1_s {
float s[16];
};
+/* --- TEL0..3 - TELEMETRY STATUS --- */
+#define LOG_TEL0_MSG 34
+#define LOG_TEL1_MSG 35
+#define LOG_TEL2_MSG 36
+#define LOG_TEL3_MSG 37
+struct log_TEL_s {
+ uint8_t rssi;
+ uint8_t remote_rssi;
+ uint8_t noise;
+ uint8_t remote_noise;
+ uint16_t rxerrors;
+ uint16_t fixed;
+ uint8_t txbuf;
+ uint64_t heartbeat_time;
+};
+
+
/********** SYSTEM MESSAGES, ID > 0x80 **********/
/* --- TIME - TIME STAMP --- */
@@ -432,7 +438,10 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"),
LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"),
LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"),
- LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"),
+ LOG_FORMAT_S(TEL0, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL1, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL2, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
+ LOG_FORMAT_S(TEL3, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"),
LOG_FORMAT(EST0, "ffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,nStat,fNaN,fHealth,fTOut"),
LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"),
LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"),
diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index c8a3ec8f0..5deb471d6 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -665,6 +665,15 @@ PARAM_DEFINE_INT32(RC_MAP_LOITER_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ACRO_SW, 0);
/**
+ * Offboard switch channel mapping.
+ *
+ * @min 0
+ * @max 18
+ * @group Radio Calibration
+ */
+PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
+
+/**
* Flaps channel mapping.
*
* @min 0
@@ -811,3 +820,20 @@ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f);
*
*/
PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f);
+
+
+/**
+ * Threshold for selecting offboard mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel<th
+ *
+ */
+PARAM_DEFINE_FLOAT(RC_OFFB_TH, 0.5f);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 3307354a0..6e2d906e6 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -266,6 +266,7 @@ private:
int rc_map_posctl_sw;
int rc_map_loiter_sw;
int rc_map_acro_sw;
+ int rc_map_offboard_sw;
int rc_map_flaps;
@@ -282,12 +283,14 @@ private:
float rc_return_th;
float rc_loiter_th;
float rc_acro_th;
+ float rc_offboard_th;
bool rc_assist_inv;
bool rc_auto_inv;
bool rc_posctl_inv;
bool rc_return_inv;
bool rc_loiter_inv;
bool rc_acro_inv;
+ bool rc_offboard_inv;
float battery_voltage_scaling;
float battery_current_scaling;
@@ -321,6 +324,7 @@ private:
param_t rc_map_posctl_sw;
param_t rc_map_loiter_sw;
param_t rc_map_acro_sw;
+ param_t rc_map_offboard_sw;
param_t rc_map_flaps;
@@ -337,6 +341,7 @@ private:
param_t rc_return_th;
param_t rc_loiter_th;
param_t rc_acro_th;
+ param_t rc_offboard_th;
param_t battery_voltage_scaling;
param_t battery_current_scaling;
@@ -540,6 +545,7 @@ Sensors::Sensors() :
_parameter_handles.rc_map_posctl_sw = param_find("RC_MAP_POSCTL_SW");
_parameter_handles.rc_map_loiter_sw = param_find("RC_MAP_LOITER_SW");
_parameter_handles.rc_map_acro_sw = param_find("RC_MAP_ACRO_SW");
+ _parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW");
_parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1");
_parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2");
@@ -555,6 +561,7 @@ Sensors::Sensors() :
_parameter_handles.rc_return_th = param_find("RC_RETURN_TH");
_parameter_handles.rc_loiter_th = param_find("RC_LOITER_TH");
_parameter_handles.rc_acro_th = param_find("RC_ACRO_TH");
+ _parameter_handles.rc_offboard_th = param_find("RC_OFFB_TH");
/* gyro offsets */
_parameter_handles.gyro_offset[0] = param_find("SENS_GYRO_XOFF");
@@ -707,6 +714,10 @@ Sensors::parameters_update()
warnx("%s", paramerr);
}
+ if (param_get(_parameter_handles.rc_map_offboard_sw, &(_parameters.rc_map_offboard_sw)) != OK) {
+ warnx("%s", paramerr);
+ }
+
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx("%s", paramerr);
}
@@ -735,6 +746,9 @@ Sensors::parameters_update()
param_get(_parameter_handles.rc_acro_th, &(_parameters.rc_acro_th));
_parameters.rc_acro_inv = (_parameters.rc_acro_th < 0);
_parameters.rc_acro_th = fabs(_parameters.rc_acro_th);
+ param_get(_parameter_handles.rc_offboard_th, &(_parameters.rc_offboard_th));
+ _parameters.rc_offboard_inv = (_parameters.rc_offboard_th < 0);
+ _parameters.rc_offboard_th = fabs(_parameters.rc_offboard_th);
/* update RC function mappings */
_rc.function[THROTTLE] = _parameters.rc_map_throttle - 1;
@@ -747,6 +761,7 @@ Sensors::parameters_update()
_rc.function[POSCTL] = _parameters.rc_map_posctl_sw - 1;
_rc.function[LOITER] = _parameters.rc_map_loiter_sw - 1;
_rc.function[ACRO] = _parameters.rc_map_acro_sw - 1;
+ _rc.function[OFFBOARD] = _parameters.rc_map_offboard_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
@@ -1545,6 +1560,7 @@ Sensors::rc_poll()
manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
manual.acro_switch = get_rc_sw2pos_position(ACRO, _parameters.rc_acro_th, _parameters.rc_acro_inv);
+ manual.offboard_switch = get_rc_sw2pos_position(OFFBOARD, _parameters.rc_offboard_th, _parameters.rc_offboard_inv);
/* publish manual_control_setpoint topic */
if (_manual_control_pub > 0) {
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index ccc516f39..7aa2f3a5f 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -67,7 +67,7 @@ __EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pT
__EXPORT struct system_load_s system_load;
-extern FAR struct _TCB *sched_gettcb(pid_t pid);
+extern FAR struct tcb_s *sched_gettcb(pid_t pid);
void cpuload_initialize_once()
{
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 9fff3eb88..90d8dd77c 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -54,6 +54,9 @@
#include "systemlib.h"
+// Didn't seem right to include up_internal.h, so direct extern instead.
+extern void up_systemreset(void) noreturn_function;
+
void
systemreset(bool to_bootloader)
{
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index 687fc1d4a..9b118205e 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -186,7 +186,10 @@ ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
#include "topics/telemetry_status.h"
-ORB_DEFINE(telemetry_status, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_0, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_1, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_2, struct telemetry_status_s);
+ORB_DEFINE(telemetry_status_3, struct telemetry_status_s);
#include "topics/debug_key_value.h"
ORB_DEFINE(debug_key_value, struct debug_key_value_s);
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index 910b8a623..dde237adc 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -98,6 +98,7 @@ struct manual_control_setpoint_s {
switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
+ switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
}; /**< manual control inputs */
/**
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index 68d3e494b..d7b131e3c 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -69,7 +69,7 @@ struct offboard_control_setpoint_s {
uint64_t timestamp;
enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
- bool armed; /**< Armed flag set, yes / no */
+
float p1; /**< ailerons roll / roll rate input */
float p2; /**< elevator / pitch / pitch rate */
float p3; /**< rudder / yaw rate / yaw */
diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h
index ce42035ba..673c0e491 100644
--- a/src/modules/uORB/topics/position_setpoint_triplet.h
+++ b/src/modules/uORB/topics/position_setpoint_triplet.h
@@ -60,16 +60,26 @@ enum SETPOINT_TYPE
SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */
SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */
SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */
+ SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */
};
struct position_setpoint_s
{
bool valid; /**< true if setpoint is valid */
enum SETPOINT_TYPE type; /**< setpoint type to adjust behavior of position controller */
+ float x; /**< local position setpoint in m in NED */
+ float y; /**< local position setpoint in m in NED */
+ float z; /**< local position setpoint in m in NED */
+ bool position_valid; /**< true if local position setpoint valid */
+ float vx; /**< local velocity setpoint in m in NED */
+ float vy; /**< local velocity setpoint in m in NED */
+ float vz; /**< local velocity setpoint in m in NED */
+ bool velocity_valid; /**< true if local velocity setpoint valid */
double lat; /**< latitude, in deg */
double lon; /**< longitude, in deg */
float alt; /**< altitude AMSL, in m */
float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */
+ float yawspeed; /**< yawspeed (only for multirotors, in rad/s) */
float loiter_radius; /**< loiter radius (only for fixed wing), in m */
int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */
float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 829d8e57d..8978de471 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -56,7 +56,7 @@ enum RC_CHANNELS_FUNCTION {
RETURN,
POSCTL,
LOITER,
- OFFBOARD_MODE,
+ OFFBOARD,
ACRO,
FLAPS,
AUX_1,
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index e9e00d76c..3347724a5 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -72,6 +72,28 @@ struct telemetry_status_s {
* @}
*/
-ORB_DECLARE(telemetry_status);
+ORB_DECLARE(telemetry_status_0);
+ORB_DECLARE(telemetry_status_1);
+ORB_DECLARE(telemetry_status_2);
+ORB_DECLARE(telemetry_status_3);
+
+#define TELEMETRY_STATUS_ORB_ID_NUM 4
+
+static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_ID_NUM] = {
+ ORB_ID(telemetry_status_0),
+ ORB_ID(telemetry_status_1),
+ ORB_ID(telemetry_status_2),
+ ORB_ID(telemetry_status_3),
+};
+
+// This is a hack to quiet an unused-variable warning for when telemetry_status.h is
+// included but telemetry_status_orb_id is not referenced. The inline works if you
+// choose to use it, but you can continue to just directly index into the array as well.
+// If you don't use the inline this ends up being a no-op with no additional code emitted.
+extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index);
+extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index)
+{
+ return telemetry_status_orb_id[index];
+}
#endif /* TOPIC_TELEMETRY_STATUS_H */
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index ea554006f..49e2ba4b5 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -74,6 +74,7 @@ struct vehicle_control_mode_s {
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
bool flag_control_auto_enabled; /**< true if onboard autopilot should act */
+ bool flag_control_offboard_enabled; /**< true if offboard control should be used */
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 56590047f..b46c00b75 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -70,7 +70,8 @@ typedef enum {
MAIN_STATE_AUTO_LOITER,
MAIN_STATE_AUTO_RTL,
MAIN_STATE_ACRO,
- MAIN_STATE_MAX,
+ MAIN_STATE_OFFBOARD,
+ MAIN_STATE_MAX
} main_state_t;
// If you change the order, add or remove arming_state_t states make sure to update the arrays
@@ -106,6 +107,7 @@ typedef enum {
NAVIGATION_STATE_LAND, /**< Land mode */
NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
NAVIGATION_STATE_TERMINATION, /**< Termination mode */
+ NAVIGATION_STATE_OFFBOARD,
NAVIGATION_STATE_MAX,
} navigation_state_t;