AP_RPM: remove unneeded initialisations

These should always be static
This commit is contained in:
Peter Barker 2018-07-23 14:06:55 +10:00 committed by Randy Mackay
parent d3877bf2d0
commit ec6e2b9da8
2 changed files with 2 additions and 7 deletions

View File

@ -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));
}
/*

View File

@ -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};