mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Compass_AK8963: move variable declarations before goto
This commit is contained in:
parent
3fc47b33e8
commit
63973bff31
@ -239,6 +239,10 @@ void AP_Compass_AK8963::_update()
|
|||||||
{
|
{
|
||||||
struct AP_AK8963_SerialBus::raw_value rv;
|
struct AP_AK8963_SerialBus::raw_value rv;
|
||||||
float mag_x, mag_y, mag_z;
|
float mag_x, mag_y, mag_z;
|
||||||
|
// get raw_field - sensor frame, uncorrected
|
||||||
|
Vector3f raw_field = Vector3f(mag_x, mag_y, mag_z);
|
||||||
|
uint32_t time_us = hal.scheduler->micros();
|
||||||
|
|
||||||
|
|
||||||
if (hal.scheduler->micros() - _last_update_timestamp < 10000) {
|
if (hal.scheduler->micros() - _last_update_timestamp < 10000) {
|
||||||
goto end;
|
goto end;
|
||||||
@ -263,9 +267,6 @@ void AP_Compass_AK8963::_update()
|
|||||||
if (is_zero(mag_x) && is_zero(mag_y) && is_zero(mag_z)) {
|
if (is_zero(mag_x) && is_zero(mag_y) && is_zero(mag_z)) {
|
||||||
goto fail;
|
goto fail;
|
||||||
}
|
}
|
||||||
uint32_t time_us = hal.scheduler->micros();
|
|
||||||
// get raw_field - sensor frame, uncorrected
|
|
||||||
Vector3f raw_field = Vector3f(mag_x, mag_y, mag_z);
|
|
||||||
|
|
||||||
// rotate raw_field from sensor frame to body frame
|
// rotate raw_field from sensor frame to body frame
|
||||||
rotate_field(raw_field, _compass_instance);
|
rotate_field(raw_field, _compass_instance);
|
||||||
|
Loading…
Reference in New Issue
Block a user