mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Copter: initialise G_Dt to 1.0/400
This commit is contained in:
parent
8907cb3b23
commit
00ec3efb48
@ -48,7 +48,9 @@ void Copter::init_ardupilot()
|
||||
// load parameters from EEPROM
|
||||
load_parameters();
|
||||
|
||||
G_Dt = scheduler.get_loop_period_s();
|
||||
// time per loop - this gets updated in the main loop() based on
|
||||
// actual loop rate
|
||||
G_Dt = 1.0/400;
|
||||
|
||||
// initialise stats module
|
||||
g2.stats.init();
|
||||
|
Loading…
Reference in New Issue
Block a user