Plane: enable wind estimation

This commit is contained in:
Andrew Tridgell 2013-05-24 11:21:32 +10:00
parent 14628990e6
commit a22f5e3bc4
3 changed files with 5 additions and 0 deletions

View File

@ -393,6 +393,7 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv)
ahrs.init(); ahrs.init();
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ins.init(AP_InertialSensor::COLD_START, ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate, ins_sample_rate,

View File

@ -220,6 +220,7 @@ static void init_ardupilot()
//read_EEPROM_airstart_critical(); //read_EEPROM_airstart_critical();
ahrs.init(); ahrs.init();
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ins.init(AP_InertialSensor::WARM_START, ins.init(AP_InertialSensor::WARM_START,
ins_sample_rate, ins_sample_rate,
@ -448,6 +449,7 @@ static void startup_INS_ground(bool do_accel_init)
ahrs.init(); ahrs.init();
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ins.init(AP_InertialSensor::COLD_START, ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate, ins_sample_rate,

View File

@ -471,6 +471,7 @@ test_ins(uint8_t argc, const Menu::arg *argv)
//cliSerial->printf_P(PSTR("Calibrating.")); //cliSerial->printf_P(PSTR("Calibrating."));
ahrs.init(); ahrs.init();
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ins.init(AP_InertialSensor::COLD_START, ins.init(AP_InertialSensor::COLD_START,
ins_sample_rate, ins_sample_rate,
@ -532,6 +533,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
} }
ahrs.init(); ahrs.init();
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true);
ahrs.set_compass(&compass); ahrs.set_compass(&compass);
report_compass(); report_compass();