From ec6e2b9da8d5a7a1ff0b036b7403d220e79557b9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 23 Jul 2018 14:06:55 +1000 Subject: [PATCH] AP_RPM: remove unneeded initialisations These should always be static --- libraries/AP_RPM/AP_RPM.cpp | 7 +------ libraries/AP_RPM/RPM_PX4_PWM.h | 2 +- 2 files changed, 2 insertions(+), 7 deletions(-) diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index fb53426a81..025b207ba4 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -90,14 +90,9 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = { AP_GROUPEND }; -AP_RPM::AP_RPM(void) : - num_instances(0) +AP_RPM::AP_RPM(void) { AP_Param::setup_object_defaults(this, var_info); - - // init state and drivers - memset(state,0,sizeof(state)); - memset(drivers,0,sizeof(drivers)); } /* diff --git a/libraries/AP_RPM/RPM_PX4_PWM.h b/libraries/AP_RPM/RPM_PX4_PWM.h index 125484c60b..a86af95fd0 100644 --- a/libraries/AP_RPM/RPM_PX4_PWM.h +++ b/libraries/AP_RPM/RPM_PX4_PWM.h @@ -34,7 +34,7 @@ public: private: int _fd = -1; int _logfd = -1; - uint64_t _last_timestamp = 0; + uint64_t _last_timestamp; uint32_t _resolution_usec = 1; ModeFilterFloat_Size5 signal_quality_filter {3};