mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: review fixes
This commit is contained in:
parent
4e33b74d69
commit
b73131cdbc
@ -604,8 +604,8 @@ public:
|
||||
return _rsem;
|
||||
}
|
||||
|
||||
// active EKF type for logging
|
||||
virtual uint8_t get_active_EKF_type(void) const { return 0; }
|
||||
// active AHRS type for logging
|
||||
virtual uint8_t get_active_AHRS_type(void) const { return 0; }
|
||||
|
||||
// for holding parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
@ -1161,10 +1161,10 @@ bool AP_AHRS_NavEKF::get_relative_position_NED_origin(Vector3f &vec) const
|
||||
#endif
|
||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||
case EKFType::EXTERNAL: {
|
||||
auto &serahrs = AP::externalAHRS();
|
||||
auto &extahrs = AP::externalAHRS();
|
||||
Location loc, orgn;
|
||||
if (serahrs.get_origin(orgn) &&
|
||||
serahrs.get_location(loc)) {
|
||||
if (extahrs.get_origin(orgn) &&
|
||||
extahrs.get_location(loc)) {
|
||||
const Vector2f diff2d = orgn.get_distance_NE(loc);
|
||||
vec = Vector3f(diff2d.x, diff2d.y,
|
||||
-(loc.alt - orgn.alt)*0.01);
|
||||
|
@ -318,7 +318,7 @@ public:
|
||||
void set_alt_measurement_noise(float noise) override;
|
||||
|
||||
// active EKF type for logging
|
||||
uint8_t get_active_EKF_type(void) const override {
|
||||
uint8_t get_active_AHRS_type(void) const override {
|
||||
return uint8_t(active_EKF_type());
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user