mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: Thread: allow to use Thread from stack
Up until now we rely on Thread objects and variants thereof to be allocated on heap or embedded in another object that's zero'ed on initialization. However sometimes it's convenient to be able to use them on stack as will be the case when writting unit tests. Initialize all relevant fields to allow them to be used on stack. While at it, prefer C++11 initialization on Poller since it's only setting the default (invalid) value.
This commit is contained in:
parent
c430bb29e3
commit
da821e69eb
|
@ -30,7 +30,7 @@ class Pollable {
|
|||
friend class Poller;
|
||||
public:
|
||||
Pollable(int fd) : _fd(fd) { }
|
||||
Pollable() : _fd(-1) { }
|
||||
Pollable() { }
|
||||
|
||||
virtual ~Pollable();
|
||||
|
||||
|
@ -42,7 +42,7 @@ public:
|
|||
virtual void on_hang_up() { }
|
||||
|
||||
protected:
|
||||
int _fd;
|
||||
int _fd = -1;
|
||||
};
|
||||
|
||||
class Poller {
|
||||
|
|
|
@ -56,7 +56,7 @@ protected:
|
|||
|
||||
PeriodicCb _cb;
|
||||
WrapperCb *_wrapper;
|
||||
bool _removeme;
|
||||
bool _removeme = false;
|
||||
};
|
||||
|
||||
|
||||
|
@ -76,7 +76,7 @@ protected:
|
|||
void _cleanup_timers();
|
||||
|
||||
Poller _poller{};
|
||||
std::vector<TimerPollable*> _timers;
|
||||
std::vector<TimerPollable*> _timers{};
|
||||
};
|
||||
|
||||
}
|
||||
|
|
|
@ -229,6 +229,10 @@ bool Thread::set_stack_size(size_t stack_size)
|
|||
|
||||
bool PeriodicThread::_run()
|
||||
{
|
||||
if (_period_usec == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint64_t next_run_usec = AP_HAL::micros64() + _period_usec;
|
||||
|
||||
while (true) {
|
||||
|
|
|
@ -58,15 +58,15 @@ protected:
|
|||
void _poison_stack();
|
||||
|
||||
task_t _task;
|
||||
bool _started;
|
||||
pthread_t _ctx;
|
||||
bool _started = false;
|
||||
pthread_t _ctx = 0;
|
||||
|
||||
struct stack_debug {
|
||||
uint32_t *start;
|
||||
uint32_t *end;
|
||||
} _stack_debug;
|
||||
|
||||
size_t _stack_size;
|
||||
size_t _stack_size = 0;
|
||||
};
|
||||
|
||||
class PeriodicThread : public Thread {
|
||||
|
@ -80,7 +80,7 @@ public:
|
|||
protected:
|
||||
bool _run() override;
|
||||
|
||||
uint64_t _period_usec;
|
||||
uint64_t _period_usec = 0;
|
||||
};
|
||||
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue