mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
ArduCopter: clear ahrs roll and pitch trims after an accel level command
This commit is contained in:
parent
ff9902c5d6
commit
e9c1500f33
@ -1090,7 +1090,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
if (packet.param1 == 1 ||
|
||||
packet.param2 == 1 ||
|
||||
packet.param3 == 1) {
|
||||
ins.init_accel(mavlink_delay, flash_leds);
|
||||
ins.init_accel(mavlink_delay, flash_leds); // level accelerometer values
|
||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
||||
}
|
||||
if (packet.param4 == 1) {
|
||||
trim_radio();
|
||||
|
@ -250,7 +250,8 @@ setup_accel(uint8_t argc, const Menu::arg *argv)
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
ins_sample_rate,
|
||||
delay, flash_leds, &timer_scheduler);
|
||||
ins.init_accel(delay, flash_leds);
|
||||
ins.init_accel(delay, flash_leds); // level accelerometer values
|
||||
ahrs.set_trim(Vector3f(0,0,0)); // clear out saved trim
|
||||
report_ins();
|
||||
return(0);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user