mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: compass init never fails
This commit is contained in:
parent
069a2d0e35
commit
d489d9a585
@ -117,7 +117,8 @@ void Plane::init_ardupilot()
|
|||||||
airspeed.init();
|
airspeed.init();
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
bool compass_ok = compass.init() && compass.read();
|
compass.init();
|
||||||
|
bool compass_ok = compass.read();
|
||||||
#if HIL_SUPPORT
|
#if HIL_SUPPORT
|
||||||
if (g.hil_mode != 0) {
|
if (g.hil_mode != 0) {
|
||||||
compass_ok = true;
|
compass_ok = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user