mirror of https://github.com/ArduPilot/ardupilot
Plane: update for new INS API
This commit is contained in:
parent
394645560a
commit
650ff258db
|
@ -761,9 +761,8 @@ void setup() {
|
||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
uint32_t timer = millis();
|
uint32_t timer = millis();
|
||||||
// We want this to execute at 50Hz, but synchronised with the gyro/accel
|
// We want this to execute at 50Hz, synchronised with the gyro/accel
|
||||||
uint16_t num_samples = ins.num_samples_available();
|
if (ins.sample_available()) {
|
||||||
if (num_samples >= 1) {
|
|
||||||
delta_ms_fast_loop = timer - fast_loopTimer_ms;
|
delta_ms_fast_loop = timer - fast_loopTimer_ms;
|
||||||
G_Dt = delta_ms_fast_loop * 0.001f;
|
G_Dt = delta_ms_fast_loop * 0.001f;
|
||||||
fast_loopTimer_ms = timer;
|
fast_loopTimer_ms = timer;
|
||||||
|
|
Loading…
Reference in New Issue