5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-03-10 00:23:57 -03:00

uncrustify libraries/AP_Common/AP_Loop.h

This commit is contained in:
uncrustify 2012-08-16 23:18:11 -07:00 committed by Pat Hickey
parent 0ed851024e
commit f45a727fe6

View File

@ -24,35 +24,36 @@
class Loop class Loop
{ {
public: public:
Loop() : _fptr(), _data(), _period(), _subLoops(), _timeStamp(), _load(), _dt() {}; Loop() : _fptr(), _data(), _period(), _subLoops(), _timeStamp(), _load(), _dt() {
};
Loop(float frequency, void (*fptr)(void *) = NULL, void * data = NULL); Loop(float frequency, void (*fptr)(void *) = NULL, void * data = NULL);
void update(); void update();
Vector<Loop *> & subLoops() { Vector<Loop *> & subLoops() {
return _subLoops; return _subLoops;
} }
float frequency() { float frequency() {
return 1.0e6/_period; return 1.0e6/_period;
} }
void frequency(float _frequency) { void frequency(float _frequency) {
_period = 1e6/_frequency; _period = 1e6/_frequency;
} }
uint32_t timeStamp() { uint32_t timeStamp() {
return _timeStamp; return _timeStamp;
} }
float dt() { float dt() {
return _dt; return _dt;
} }
uint8_t load() { uint8_t load() {
return _load; return _load;
} }
protected: protected:
void (*_fptr)(void *); void (*_fptr)(void *);
void * _data; void * _data;
uint32_t _period; uint32_t _period;
Vector<Loop *> _subLoops; Vector<Loop *> _subLoops;
uint32_t _timeStamp; uint32_t _timeStamp;
uint8_t _load; uint8_t _load;
float _dt; float _dt;
}; };
#endif #endif