mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Rover: integrate automatic roll and pitch trims
This commit is contained in:
parent
9c984b18db
commit
b7a4814e22
@ -296,13 +296,17 @@ setup_erase(uint8_t argc, const Menu::arg *argv)
|
||||
static int8_t
|
||||
setup_accel_scale(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
float trim_roll, trim_pitch;
|
||||
cliSerial->println_P(PSTR("Initialising gyros"));
|
||||
ahrs.init();
|
||||
ins.init(AP_InertialSensor::COLD_START,
|
||||
ins_sample_rate,
|
||||
flash_leds);
|
||||
AP_InertialSensor_UserInteractStream interact(hal.console);
|
||||
ins.calibrate_accel(flash_leds, &interact);
|
||||
if(ins.calibrate_accel(flash_leds, &interact, trim_roll, trim_pitch)) {
|
||||
// reset ahrs's trim to suggested values from calibration routine
|
||||
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
|
||||
}
|
||||
return(0);
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user