Add a CLI setup action to reset the magnetometer offsets

Since the magnetometer offsets are not available through the MAVLink parameter interface (since they are an AP_Var vector) this little feature allows them to be reset from the CLI.  Useful if you somehow get bad offsets or if you change magnetometer.  If you have a bad set of large offset values I have seen issues with the nulling algorithm have trouble converging to the proper values.  I have never seen it have trouble converging from 0/0/0, so this could be a useful feature from time to time.
This commit is contained in:
Doug Weibel 2012-01-15 16:15:08 -07:00
parent 6e8ac99ed6
commit e22a83eec0
2 changed files with 4 additions and 3 deletions

View File

@ -301,8 +301,11 @@ setup_compass(uint8_t argc, const Menu::arg *argv)
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.compass_enabled = false;
} else if (!strcmp_P(argv[1].str, PSTR("reset"))) {
compass.set_offsets(0,0,0);
} else {
Serial.printf_P(PSTR("\nOptions:[on,off]\n"));
Serial.printf_P(PSTR("\nOptions:[on,off,reset]\n"));
report_compass();
return 0;
}

View File

@ -102,8 +102,6 @@ public:
/// Program new offset values.
///
/// XXX DEPRECATED
///
/// @param x Offset to the raw mag_x value.
/// @param y Offset to the raw mag_y value.
/// @param z Offset to the raw mag_z value.