mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: integrate automatic roll and pitch trims
This commit is contained in:
parent
ccdbfefb73
commit
5b50f31b8f
@ -1096,8 +1096,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
trim_radio();
|
trim_radio();
|
||||||
}
|
}
|
||||||
if (packet.param5 == 1) {
|
if (packet.param5 == 1) {
|
||||||
|
float trim_roll, trim_pitch;
|
||||||
// this blocks
|
// this blocks
|
||||||
ins.calibrate_accel(mavlink_delay, flash_leds, gcs_send_text_fmt, setup_wait_key);
|
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
|
||||||
|
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||||
}
|
}
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
break;
|
break;
|
||||||
|
@ -284,11 +284,15 @@ static void setup_wait_key(void)
|
|||||||
static int8_t
|
static int8_t
|
||||||
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
|
float trim_roll, trim_pitch;
|
||||||
|
|
||||||
cliSerial->println_P(PSTR("Initialising gyros"));
|
cliSerial->println_P(PSTR("Initialising gyros"));
|
||||||
ins.init(AP_InertialSensor::COLD_START,
|
ins.init(AP_InertialSensor::COLD_START,
|
||||||
ins_sample_rate,
|
ins_sample_rate,
|
||||||
delay, flash_leds, &timer_scheduler);
|
delay, flash_leds, &timer_scheduler);
|
||||||
ins.calibrate_accel(delay, flash_leds, setup_printf_P, setup_wait_key);
|
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
|
||||||
|
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||||
report_ins();
|
report_ins();
|
||||||
return(0);
|
return(0);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user