Copter: limit max ahrs trim to 10degrees

Limit is applied as trims from accelerometer calibration are copied to
the ahrs object.
This commit is contained in:
Randy Mackay 2013-02-02 10:59:58 +09:00
parent d6edde93b4
commit 4c40b44563
2 changed files with 4 additions and 0 deletions

View File

@ -1100,6 +1100,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// this blocks
ins.calibrate_accel(mavlink_delay, flash_leds, gcs_send_text_fmt, setup_wait_key, trim_roll, trim_pitch);
// reset ahrs's trim to suggested values from calibration routine
trim_roll = constrain(trim_roll, ToRad(-10.0f), ToRad(10.0f));
trim_pitch = constrain(trim_pitch, ToRad(-10.0f), ToRad(10.0f));
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
result = MAV_RESULT_ACCEPTED;

View File

@ -292,6 +292,8 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
delay, flash_leds, &timer_scheduler);
ins.calibrate_accel(delay, flash_leds, setup_printf_P, setup_wait_key, trim_roll, trim_pitch);
// reset ahrs's trim to suggested values from calibration routine
trim_roll = constrain(trim_roll, ToRad(-10.0f), ToRad(10.0f));
trim_pitch = constrain(trim_pitch, ToRad(-10.0f), ToRad(10.0f));
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
report_ins();
return(0);