mirror of https://github.com/ArduPilot/ardupilot
INS: make calibrate_accel() return a bool
this will allow APM to auto set MANUAL_LEVEL to 1
This commit is contained in:
parent
152c12c283
commit
9c811671f1
|
@ -232,7 +232,7 @@ AP_InertialSensor::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_l
|
||||||
}
|
}
|
||||||
|
|
||||||
// perform accelerometer calibration including providing user instructions and feedback
|
// perform accelerometer calibration including providing user instructions and feedback
|
||||||
void AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on), void (*send_msg)(const prog_char_t *, ...))
|
bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on), void (*send_msg)(const prog_char_t *, ...))
|
||||||
{
|
{
|
||||||
Vector3f samples[6];
|
Vector3f samples[6];
|
||||||
Vector3f new_offsets;
|
Vector3f new_offsets;
|
||||||
|
@ -274,9 +274,9 @@ void AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
if (send_msg == NULL) {
|
if (send_msg == NULL) {
|
||||||
Serial.printf_P(PSTR("USER: Place APM %S and press any key.\n"), msg);
|
|
||||||
}else{
|
|
||||||
send_msg(PSTR("USER: Place APM %S and press any key.\n"), msg);
|
send_msg(PSTR("USER: Place APM %S and press any key.\n"), msg);
|
||||||
|
}else{
|
||||||
|
Serial.printf_P(PSTR("USER: Place APM %S and press any key.\n"), msg);
|
||||||
}
|
}
|
||||||
|
|
||||||
// wait for user input
|
// wait for user input
|
||||||
|
@ -305,29 +305,28 @@ void AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void
|
||||||
|
|
||||||
// run the calibration routine
|
// run the calibration routine
|
||||||
if( _calibrate_accel(samples, new_offsets, new_scaling) ) {
|
if( _calibrate_accel(samples, new_offsets, new_scaling) ) {
|
||||||
|
|
||||||
if (send_msg == NULL) {
|
if (send_msg == NULL) {
|
||||||
Serial.printf_P(PSTR("Calibration successful\n"));
|
|
||||||
}else{
|
|
||||||
send_msg(PSTR("Calibration successful\n"));
|
send_msg(PSTR("Calibration successful\n"));
|
||||||
|
}else{
|
||||||
|
Serial.printf_P(PSTR("Calibration successful\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
// set and save calibration
|
// set and save calibration
|
||||||
_accel_offset.set(new_offsets);
|
_accel_offset.set(new_offsets);
|
||||||
_accel_scale.set(new_scaling);
|
_accel_scale.set(new_scaling);
|
||||||
_save_parameters();
|
_save_parameters();
|
||||||
}else{
|
return true;
|
||||||
if (send_msg == NULL) {
|
|
||||||
Serial.printf_P(PSTR("Calibration failed\n"));
|
|
||||||
}else{
|
|
||||||
send_msg(PSTR("Calibration failed\n"));
|
|
||||||
}
|
|
||||||
|
|
||||||
// restore original scaling and offsets
|
|
||||||
_accel_offset.set(orig_offset);
|
|
||||||
_accel_scale.set(orig_scale);
|
|
||||||
}
|
}
|
||||||
delay_cb(100);
|
|
||||||
|
if (send_msg == NULL) {
|
||||||
|
send_msg(PSTR("Calibration failed\n"));
|
||||||
|
} else {
|
||||||
|
Serial.printf_P(PSTR("Calibration failed\n"));
|
||||||
|
}
|
||||||
|
// restore original scaling and offsets
|
||||||
|
_accel_offset.set(orig_offset);
|
||||||
|
_accel_scale.set(orig_scale);
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// _calibrate_model - perform low level accel calibration
|
// _calibrate_model - perform low level accel calibration
|
||||||
|
|
|
@ -50,7 +50,7 @@ public:
|
||||||
virtual void init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on));
|
virtual void init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on));
|
||||||
|
|
||||||
// perform accelerometer calibration including providing user instructions and feedback
|
// perform accelerometer calibration including providing user instructions and feedback
|
||||||
virtual void calibrate_accel(void (*delay_cb)(unsigned long t),
|
virtual bool calibrate_accel(void (*delay_cb)(unsigned long t),
|
||||||
void (*flash_leds_cb)(bool on) = NULL,
|
void (*flash_leds_cb)(bool on) = NULL,
|
||||||
void (*send_msg)(const prog_char_t *, ...) = NULL);
|
void (*send_msg)(const prog_char_t *, ...) = NULL);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue