AHRS: fix example sketch to use roll/pitch trim

This commit is contained in:
Randy Mackay 2013-02-19 18:56:09 +09:00
parent 3321db8dde
commit 963231a19b

View File

@ -102,6 +102,7 @@ void loop(void)
void run_calibration() void run_calibration()
{ {
float roll_trim, pitch_trim;
// clear off any other characters (like line feeds,etc) // clear off any other characters (like line feeds,etc)
while( hal.console->available() ) { while( hal.console->available() ) {
hal.console->read(); hal.console->read();
@ -110,7 +111,7 @@ void run_calibration()
#if !defined( __AVR_ATmega1280__ ) #if !defined( __AVR_ATmega1280__ )
AP_InertialSensor_UserInteractStream interact(hal.console); AP_InertialSensor_UserInteractStream interact(hal.console);
ins.calibrate_accel(NULL, &interact); ins.calibrate_accel(NULL, &interact, roll_trim, pitch_trim);
#else #else
hal.console->println_P(PSTR("calibrate_accel not available on 1280")); hal.console->println_P(PSTR("calibrate_accel not available on 1280"));
#endif #endif