Plane: support setting just accel trim with preflight-cal

use param5==2
This commit is contained in:
Andrew Tridgell 2015-05-16 07:28:59 +10:00
parent aac652a1b4
commit 9ceee3cea7
1 changed files with 10 additions and 0 deletions

View File

@ -1082,6 +1082,16 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else { } else {
result = MAV_RESULT_FAILED; result = MAV_RESULT_FAILED;
} }
} else if (is_equal(packet.param5,2.0f)) {
// accel trim
float trim_roll, trim_pitch;
if(ins.calibrate_trim(trim_roll, trim_pitch)) {
// reset ahrs's trim to suggested values from calibration routine
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;
}
} }
else { else {
send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration")); send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration"));