mirror of https://github.com/ArduPilot/ardupilot
added call to APM_Compass.SetOffsets. This is just to make it easier for people to figure out how to set the values.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@667 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e29ea04fb1
commit
24202b7c46
|
@ -374,6 +374,7 @@ void setup()
|
|||
if (MAGNETOMETER == 1) {
|
||||
APM_Compass.Init(); // I2C initialization
|
||||
APM_Compass.SetOrientation(APM_COMPASS_COMPONENTS_UP_PINS_BACK);
|
||||
APM_Compass.SetOffsets(0,0,0);
|
||||
APM_Compass.SetDeclination(ToRad(0.0));
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue