mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_RPM: move RPM sensor logging into AP_RPM
This commit is contained in:
parent
15e99e306d
commit
99a3d253db
@ -20,6 +20,8 @@
|
|||||||
#include "RPM_HarmonicNotch.h"
|
#include "RPM_HarmonicNotch.h"
|
||||||
#include "RPM_ESC_Telem.h"
|
#include "RPM_ESC_Telem.h"
|
||||||
|
|
||||||
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
@ -186,6 +188,10 @@ void AP_RPM::update(void)
|
|||||||
drivers[i]->update();
|
drivers[i]->update();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (enabled(0) || enabled(1)) {
|
||||||
|
AP::logger().Write_RPM(*this);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user