mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
DCM: prevent a segmentation fault when compass is not enabled
when compass is disabled _compass is NULL
This commit is contained in:
parent
9846822748
commit
15d446bde2
@ -195,7 +195,9 @@ AP_DCM::accel_adjust(void)
|
|||||||
void
|
void
|
||||||
AP_DCM::matrix_reset(void)
|
AP_DCM::matrix_reset(void)
|
||||||
{
|
{
|
||||||
|
if (_compass != NULL) {
|
||||||
_compass->null_offsets_disable();
|
_compass->null_offsets_disable();
|
||||||
|
}
|
||||||
_dcm_matrix.a.x = 1.0f;
|
_dcm_matrix.a.x = 1.0f;
|
||||||
_dcm_matrix.a.y = 0.0f;
|
_dcm_matrix.a.y = 0.0f;
|
||||||
_dcm_matrix.a.z = 0.0f;
|
_dcm_matrix.a.z = 0.0f;
|
||||||
@ -208,8 +210,11 @@ AP_DCM::matrix_reset(void)
|
|||||||
_omega_I.x = 0.0f;
|
_omega_I.x = 0.0f;
|
||||||
_omega_I.y = 0.0f;
|
_omega_I.y = 0.0f;
|
||||||
_omega_I.z = 0.0f;
|
_omega_I.z = 0.0f;
|
||||||
|
if (_compass != NULL) {
|
||||||
_compass->null_offsets_enable(); // This call is needed to restart the nulling
|
_compass->null_offsets_enable(); // This call is needed to restart the nulling
|
||||||
// Otherwise the reset in the DCM matrix can mess up the nulling
|
// Otherwise the reset in the DCM matrix can mess up
|
||||||
|
// the nulling
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*************************************************
|
/*************************************************
|
||||||
|
Loading…
Reference in New Issue
Block a user