Skip to content

Commit d1983b0

Browse files
committed
AP_NavEKF3: fixup source param conversion
shorten param conversion config error if gps and optical flow are enabled we default SRC2_VELXY to optflow convert_params run from InitialiseFilter ensure param conversion only run once
1 parent 0119c48 commit d1983b0

File tree

1 file changed

+20
-5
lines changed

1 file changed

+20
-5
lines changed

libraries/AP_NavEKF3/AP_NavEKF3.cpp

Lines changed: 20 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -680,6 +680,9 @@ bool NavEKF3::InitialiseFilter(void)
680680
// expected number of IMU frames per prediction
681681
_framesPerPrediction = uint8_t((EKF_TARGET_DT / (_frameTimeUsec * 1.0e-6) + 0.5));
682682

683+
// convert parameters if necessary
684+
convert_parameters();
685+
683686
// initialise sources
684687
sources.init();
685688

@@ -1619,7 +1622,7 @@ bool NavEKF3::getDataEKFGSF(int8_t instance, float &yaw_composite, float &yaw_co
16191622
void NavEKF3::convert_parameters()
16201623
{
16211624
// exit immediately if param conversion has been done before
1622-
if (sources.any_params_configured_in_storage()) {
1625+
if (sources.configured_in_storage()) {
16231626
return;
16241627
}
16251628

@@ -1632,11 +1635,14 @@ void NavEKF3::convert_parameters()
16321635
// use EK3_GPS_TYPE to set EK3_SRC1_POSXY, EK3_SRC1_VELXY, EK3_SRC1_VELZ
16331636
const AP_Param::ConversionInfo gps_type_info = {k_param_ekf3, 1, AP_PARAM_INT8, "EK3_GPS_TYPE"};
16341637
AP_Int8 gps_type_old;
1635-
if (AP_Param::find_old_parameter(&gps_type_info, &gps_type_old)) {
1638+
const bool found_gps_type = AP_Param::find_old_parameter(&gps_type_info, &gps_type_old);
1639+
if (found_gps_type) {
16361640
switch (gps_type_old.get()) {
16371641
case 0:
1638-
// EK3_GPS_TYPE == 0 (GPS 3D Vel and 2D Pos), the default so do nothing
1639-
// sources default to EK3_SRC1_POSXY = GPS, EK3_SRC1_VELXY = GPS, EK3_SRC1_VELZ = GPS
1642+
// EK3_GPS_TYPE == 0 (GPS 3D Vel and 2D Pos)
1643+
AP_Param::set_and_save_by_name("EK3_SRC1_POSXY", (int8_t)AP_NavEKF_Source::SourceXY::GPS);
1644+
AP_Param::set_and_save_by_name("EK3_SRC1_VELXY", (int8_t)AP_NavEKF_Source::SourceXY::GPS);
1645+
AP_Param::set_and_save_by_name("EK3_SRC1_VELZ", (int8_t)AP_NavEKF_Source::SourceZ::GPS);
16401646
break;
16411647
case 1:
16421648
// EK3_GPS_TYPE == 1 (GPS 2D Vel and 2D Pos) then EK3_SRC1_POSXY = GPS(1), EK3_SRC1_VELXY = GPS(1), EK3_SRC1_VELZ = NONE(0)
@@ -1653,9 +1659,12 @@ void NavEKF3::convert_parameters()
16531659
case 3:
16541660
default:
16551661
// EK3_GPS_TYPE == 3 (No GPS) we don't know what to do, could be optical flow or external nav
1656-
AP_BoardConfig::config_error("Configure EK3_SRC1_POSXY and EK3_SRC1_VELXY");
1662+
AP_BoardConfig::config_error("Configure EK3_SRC1_POSXY and _VELXY");
16571663
break;
16581664
}
1665+
} else {
1666+
// mark configured in storage so conversion is only run once
1667+
sources.mark_configured_in_storage();
16591668
}
16601669

16611670
// use EK3_ALT_SOURCE to set EK3_SRC1_POSZ
@@ -1702,6 +1711,12 @@ void NavEKF3::convert_parameters()
17021711
// do nothing
17031712
break;
17041713
}
1714+
1715+
// if GPS and optical flow enabled set EK3_SRC2_VELXY to optical flow
1716+
// EK3_SRC_OPTIONS should default to 1 meaning both GPS and optical flow velocities will be fused
1717+
if (AP::dal().opticalflow_enabled() && (!found_gps_type || (gps_type_old.get() <= 2))) {
1718+
AP_Param::set_and_save_by_name("EK3_SRC2_VELXY", (int8_t)AP_NavEKF_Source::SourceXY::OPTFLOW);
1719+
}
17051720
}
17061721

17071722
// return data for debugging range beacon fusion

0 commit comments

Comments
 (0)