mirror of https://github.com/ArduPilot/ardupilot
AP_RPM: make Log_RPM() const
This commit is contained in:
parent
0959f926f4
commit
836042f454
|
@ -282,7 +282,7 @@ bool AP_RPM::arming_checks(size_t buflen, char *buffer) const
|
|||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
void AP_RPM::Log_RPM()
|
||||
void AP_RPM::Log_RPM() const
|
||||
{
|
||||
float rpm1 = -1, rpm2 = -1;
|
||||
|
||||
|
|
|
@ -118,7 +118,7 @@ private:
|
|||
|
||||
void detect_instance(uint8_t instance);
|
||||
|
||||
void Log_RPM();
|
||||
void Log_RPM() const;
|
||||
};
|
||||
|
||||
namespace AP {
|
||||
|
|
Loading…
Reference in New Issue