mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
AP_AHRS : set NavEKF staticMode using call to set_correct_centrigual
This commit is contained in:
parent
5c3dea28dc
commit
a87df0ad56
@ -89,6 +89,13 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void AP_AHRS_NavEKF::set_correct_centrifugal(bool setting)
|
||||||
|
{
|
||||||
|
if (ekf_started) {
|
||||||
|
EKF.SetStaticMode(setting);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// reset the current attitude, used on new IMU calibration
|
// reset the current attitude, used on new IMU calibration
|
||||||
void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
|
void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
|
||||||
{
|
{
|
||||||
@ -191,9 +198,6 @@ Vector2f AP_AHRS_NavEKF::groundspeed_vector(void)
|
|||||||
void AP_AHRS_NavEKF::set_home(int32_t lat, int32_t lng, int32_t alt_cm)
|
void AP_AHRS_NavEKF::set_home(int32_t lat, int32_t lng, int32_t alt_cm)
|
||||||
{
|
{
|
||||||
AP_AHRS_DCM::set_home(lat, lng, alt_cm);
|
AP_AHRS_DCM::set_home(lat, lng, alt_cm);
|
||||||
if (ekf_started) {
|
|
||||||
EKF.ResetPosition();
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true if inertial navigation is active
|
// return true if inertial navigation is active
|
||||||
|
Loading…
Reference in New Issue
Block a user