Plane: allow for settable main loop rate

This commit is contained in:
Andrew Tridgell 2015-12-26 14:12:39 +11:00 committed by Randy Mackay
parent 23cef70846
commit 513d5c17b9
3 changed files with 3 additions and 6 deletions

View File

@ -146,9 +146,6 @@ private:
AP_Vehicle::FixedWing aparm; AP_Vehicle::FixedWing aparm;
AP_HAL::BetterStream* cliSerial; AP_HAL::BetterStream* cliSerial;
// the rate we run the main loop
const AP_InertialSensor::Sample_rate ins_sample_rate = AP_InertialSensor::RATE_50HZ;
// Global parameters are all contained within the 'g' class. // Global parameters are all contained within the 'g' class.
Parameters g; Parameters g;

View File

@ -569,7 +569,7 @@ void Plane::startup_INS_ground(void)
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING); ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
ahrs.set_wind_estimation(true); ahrs.set_wind_estimation(true);
ins.init(ins_sample_rate); ins.init(scheduler.get_loop_rate_hz());
ahrs.reset(); ahrs.reset();
// read Baro pressure at ground // read Baro pressure at ground

View File

@ -350,7 +350,7 @@ int8_t Plane::test_ins(uint8_t argc, const Menu::arg *argv)
ahrs.set_fly_forward(true); ahrs.set_fly_forward(true);
ahrs.set_wind_estimation(true); ahrs.set_wind_estimation(true);
ins.init(ins_sample_rate); ins.init(scheduler.get_loop_rate_hz());
ahrs.reset(); ahrs.reset();
print_hit_enter(); print_hit_enter();
@ -411,7 +411,7 @@ int8_t Plane::test_mag(uint8_t argc, const Menu::arg *argv)
ahrs.set_compass(&compass); ahrs.set_compass(&compass);
// we need the AHRS initialised for this test // we need the AHRS initialised for this test
ins.init(ins_sample_rate); ins.init(scheduler.get_loop_rate_hz());
ahrs.reset(); ahrs.reset();
uint16_t counter = 0; uint16_t counter = 0;