mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_NavEKF: rename EXTERNAL to GPS
This commit is contained in:
parent
c14b4a8b6c
commit
77af6df730
@ -52,7 +52,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
|
|||||||
// @Param: 1_YAW
|
// @Param: 1_YAW
|
||||||
// @DisplayName: Yaw Source
|
// @DisplayName: Yaw Source
|
||||||
// @Description: Yaw Source
|
// @Description: Yaw Source
|
||||||
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback, 6:ExternalNav, 8:GSF
|
// @Values: 0:None, 1:Compass, 2:GPS, 3:GPS with Compass Fallback, 6:ExternalNav, 8:GSF
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("1_YAW", 5, AP_NavEKF_Source, _source_set[0].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::COMPASS),
|
AP_GROUPINFO("1_YAW", 5, AP_NavEKF_Source, _source_set[0].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::COMPASS),
|
||||||
|
|
||||||
@ -88,7 +88,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
|
|||||||
// @Param: 2_YAW
|
// @Param: 2_YAW
|
||||||
// @DisplayName: Yaw Source (Secondary)
|
// @DisplayName: Yaw Source (Secondary)
|
||||||
// @Description: Yaw Source (Secondary)
|
// @Description: Yaw Source (Secondary)
|
||||||
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback, 6:ExternalNav, 8:GSF
|
// @Values: 0:None, 1:Compass, 2:GPS, 3:GPS with Compass Fallback, 6:ExternalNav, 8:GSF
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("2_YAW", 10, AP_NavEKF_Source, _source_set[1].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
|
AP_GROUPINFO("2_YAW", 10, AP_NavEKF_Source, _source_set[1].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
|
||||||
#endif
|
#endif
|
||||||
@ -125,7 +125,7 @@ const AP_Param::GroupInfo AP_NavEKF_Source::var_info[] = {
|
|||||||
// @Param: 3_YAW
|
// @Param: 3_YAW
|
||||||
// @DisplayName: Yaw Source (Tertiary)
|
// @DisplayName: Yaw Source (Tertiary)
|
||||||
// @Description: Yaw Source (Tertiary)
|
// @Description: Yaw Source (Tertiary)
|
||||||
// @Values: 0:None, 1:Compass, 2:External, 3:External with Compass Fallback, 6:ExternalNav, 8:GSF
|
// @Values: 0:None, 1:Compass, 2:GPS, 3:GPS with Compass Fallback, 6:ExternalNav, 8:GSF
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("3_YAW", 15, AP_NavEKF_Source, _source_set[2].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
|
AP_GROUPINFO("3_YAW", 15, AP_NavEKF_Source, _source_set[2].yaw, (int8_t)AP_NavEKF_Source::SourceYaw::NONE),
|
||||||
#endif
|
#endif
|
||||||
@ -404,13 +404,13 @@ bool AP_NavEKF_Source::pre_arm_check(char *failure_msg, uint8_t failure_msg_len)
|
|||||||
// check yaw
|
// check yaw
|
||||||
switch ((SourceYaw)_source_set[i].yaw.get()) {
|
switch ((SourceYaw)_source_set[i].yaw.get()) {
|
||||||
case SourceYaw::NONE:
|
case SourceYaw::NONE:
|
||||||
case SourceYaw::EXTERNAL:
|
case SourceYaw::GPS:
|
||||||
// valid yaw value
|
// valid yaw value
|
||||||
break;
|
break;
|
||||||
case SourceYaw::COMPASS:
|
case SourceYaw::COMPASS:
|
||||||
// skip compass check for easier user setup of compass-less operation
|
// skip compass check for easier user setup of compass-less operation
|
||||||
break;
|
break;
|
||||||
case SourceYaw::EXTERNAL_COMPASS_FALLBACK:
|
case SourceYaw::GPS_COMPASS_FALLBACK:
|
||||||
compass_required = true;
|
compass_required = true;
|
||||||
break;
|
break;
|
||||||
case SourceYaw::EXTNAV:
|
case SourceYaw::EXTNAV:
|
||||||
@ -514,14 +514,14 @@ bool AP_NavEKF_Source::wheel_encoder_enabled(void) const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if ext yaw is enabled on any source
|
// return true if GPS yaw is enabled on any source
|
||||||
bool AP_NavEKF_Source::ext_yaw_enabled(void) const
|
bool AP_NavEKF_Source::gps_yaw_enabled(void) const
|
||||||
{
|
{
|
||||||
for (uint8_t i=0; i<AP_NAKEKF_SOURCE_SET_MAX; i++) {
|
for (uint8_t i=0; i<AP_NAKEKF_SOURCE_SET_MAX; i++) {
|
||||||
const auto &src = _source_set[i];
|
const auto &src = _source_set[i];
|
||||||
const SourceYaw yaw = SourceYaw(src.yaw.get());
|
const SourceYaw yaw = SourceYaw(src.yaw.get());
|
||||||
if (yaw == SourceYaw::EXTERNAL ||
|
if (yaw == SourceYaw::GPS ||
|
||||||
yaw == SourceYaw::EXTERNAL_COMPASS_FALLBACK) {
|
yaw == SourceYaw::GPS_COMPASS_FALLBACK) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -40,8 +40,8 @@ public:
|
|||||||
enum class SourceYaw : uint8_t {
|
enum class SourceYaw : uint8_t {
|
||||||
NONE = 0,
|
NONE = 0,
|
||||||
COMPASS = 1,
|
COMPASS = 1,
|
||||||
EXTERNAL = 2,
|
GPS = 2,
|
||||||
EXTERNAL_COMPASS_FALLBACK = 3,
|
GPS_COMPASS_FALLBACK = 3,
|
||||||
EXTNAV = 6,
|
EXTNAV = 6,
|
||||||
GSF = 8
|
GSF = 8
|
||||||
};
|
};
|
||||||
@ -95,8 +95,8 @@ public:
|
|||||||
// return true if ext nav is enabled on any source
|
// return true if ext nav is enabled on any source
|
||||||
bool ext_nav_enabled(void) const;
|
bool ext_nav_enabled(void) const;
|
||||||
|
|
||||||
// return true if ext yaw is enabled on any source
|
// return true if GPS yaw is enabled on any source
|
||||||
bool ext_yaw_enabled(void) const;
|
bool gps_yaw_enabled(void) const;
|
||||||
|
|
||||||
// return true if wheel encoder is enabled on any source
|
// return true if wheel encoder is enabled on any source
|
||||||
bool wheel_encoder_enabled(void) const;
|
bool wheel_encoder_enabled(void) const;
|
||||||
|
Loading…
Reference in New Issue
Block a user