mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: remove accessors only used internally
This commit is contained in:
parent
a7366729c3
commit
dc5656d34a
|
@ -2759,10 +2759,10 @@ void AP_AHRS_NavEKF::set_posvelyaw_source_set(uint8_t source_set_idx)
|
|||
void AP_AHRS_NavEKF::Log_Write()
|
||||
{
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
get_NavEKF2().Log_Write();
|
||||
EKF2.Log_Write();
|
||||
#endif
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
get_NavEKF3().Log_Write();
|
||||
EKF3.Log_Write();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -102,25 +102,6 @@ public:
|
|||
// true if compass is being used
|
||||
bool use_compass() override;
|
||||
|
||||
// we will need to remove these to fully hide which EKF we are using
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
NavEKF2 &get_NavEKF2(void) {
|
||||
return EKF2;
|
||||
}
|
||||
const NavEKF2 &get_NavEKF2_const(void) const {
|
||||
return EKF2;
|
||||
}
|
||||
#endif
|
||||
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
NavEKF3 &get_NavEKF3(void) {
|
||||
return EKF3;
|
||||
}
|
||||
const NavEKF3 &get_NavEKF3_const(void) const {
|
||||
return EKF3;
|
||||
}
|
||||
#endif
|
||||
|
||||
// return the quaternion defining the rotation from NED to XYZ (body) axes
|
||||
bool get_quaternion(Quaternion &quat) const override WARN_IF_UNUSED;
|
||||
|
||||
|
|
Loading…
Reference in New Issue