Browse Source

AP_RPM: remove unneeded initialisations

These should always be static
mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
ec6e2b9da8
  1. 7
      libraries/AP_RPM/AP_RPM.cpp
  2. 2
      libraries/AP_RPM/RPM_PX4_PWM.h

7
libraries/AP_RPM/AP_RPM.cpp

@ -90,14 +90,9 @@ const AP_Param::GroupInfo AP_RPM::var_info[] = { @@ -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));
}
/*

2
libraries/AP_RPM/RPM_PX4_PWM.h

@ -34,7 +34,7 @@ public: @@ -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};

Loading…
Cancel
Save