AP_InertialSensor: use AP_InertialSensor_UserInteract

* permits polymorphic user interaction, so we can plug in a
  pure mavlink interface
This commit is contained in:
Pat Hickey 2012-12-19 14:26:19 -08:00 committed by Andrew Tridgell
parent a2cf47e769
commit 9055681b3a
2 changed files with 9 additions and 12 deletions

View File

@ -271,7 +271,7 @@ AP_InertialSensor::_init_accel(void (*flash_leds_cb)(bool on))
// original sketch available at
// http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
AP_HAL::BetterStream* c)
AP_InertialSensor_UserInteract* interact)
{
Vector3f samples[6];
Vector3f new_offsets;
@ -312,16 +312,11 @@ bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
msg = PSTR("on it's back");
break;
}
c->printf_P(PSTR("USER: Place APM %S and press any key.\n"), msg);
interact->printf_P(
PSTR("USER: Place APM %S and press any key.\n"), msg);
// wait for user input
while (!c->available()) {
hal.scheduler->delay(20);
}
// clear input buffer
while( c->available() ) {
c->read();
}
interact->blocking_read();
// clear out any existing samples from ins
update();
@ -340,7 +335,7 @@ bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
// run the calibration routine
if( _calibrate_accel(samples, new_offsets, new_scaling) ) {
c->printf_P(PSTR("Calibration successful\n"));
interact->printf_P(PSTR("Calibration successful\n"));
// set and save calibration
_accel_offset.set(new_offsets);
@ -349,7 +344,8 @@ bool AP_InertialSensor::calibrate_accel(void (*flash_leds_cb)(bool on),
return true;
}
c->printf_P(PSTR("Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)\n"),
interact->printf_P(
PSTR("Calibration failed (%.1f %.1f %.1f %.1f %.1f %.1f)\n"),
new_offsets.x, new_offsets.y, new_offsets.z,
new_scaling.x, new_scaling.y, new_scaling.z);
// restore original scaling and offsets

View File

@ -64,7 +64,7 @@ public:
// perform accelerometer calibration including providing user instructions
// and feedback
virtual bool calibrate_accel(void (*flash_leds_cb)(bool on),
AP_HAL::BetterStream *c);
AP_InertialSensor_UserInteract *interact);
#endif
/// Perform cold-start initialisation for just the gyros.
@ -172,5 +172,6 @@ protected:
#include "AP_InertialSensor_Oilpan.h"
#include "AP_InertialSensor_MPU6000.h"
#include "AP_InertialSensor_Stub.h"
#include "AP_InertialSensor_UserInteract_Stream.h"
#endif // __AP_INERTIAL_SENSOR_H__