diff --git a/libraries/AP_HAL_Linux/Poller.h b/libraries/AP_HAL_Linux/Poller.h index 26b1c0bce2..e9dcba04d5 100644 --- a/libraries/AP_HAL_Linux/Poller.h +++ b/libraries/AP_HAL_Linux/Poller.h @@ -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 { diff --git a/libraries/AP_HAL_Linux/PollerThread.h b/libraries/AP_HAL_Linux/PollerThread.h index 9b40e85b07..c73ea5fe76 100644 --- a/libraries/AP_HAL_Linux/PollerThread.h +++ b/libraries/AP_HAL_Linux/PollerThread.h @@ -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 _timers; + std::vector _timers{}; }; } diff --git a/libraries/AP_HAL_Linux/Thread.cpp b/libraries/AP_HAL_Linux/Thread.cpp index ed26c4f168..8127c49e98 100644 --- a/libraries/AP_HAL_Linux/Thread.cpp +++ b/libraries/AP_HAL_Linux/Thread.cpp @@ -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) { diff --git a/libraries/AP_HAL_Linux/Thread.h b/libraries/AP_HAL_Linux/Thread.h index db8475fa07..ccf2ebfb73 100644 --- a/libraries/AP_HAL_Linux/Thread.h +++ b/libraries/AP_HAL_Linux/Thread.h @@ -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; }; }