AP_Logger: convert to new get_rpm() API

This commit is contained in:
Andrew Tridgell 2020-03-06 10:50:52 +11:00
parent a93aa27cc1
commit ed37ebede8
1 changed files with 7 additions and 2 deletions

View File

@ -855,11 +855,16 @@ void AP_Logger::Write_Origin(uint8_t origin_type, const Location &loc)
void AP_Logger::Write_RPM(const AP_RPM &rpm_sensor)
{
float rpm1 = -1, rpm2 = -1;
rpm_sensor.get_rpm(0, rpm1);
rpm_sensor.get_rpm(1, rpm2);
const struct log_RPM pkt{
LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
time_us : AP_HAL::micros64(),
rpm1 : rpm_sensor.get_rpm(0),
rpm2 : rpm_sensor.get_rpm(1)
rpm1 : rpm1,
rpm2 : rpm2
};
WriteBlock(&pkt, sizeof(pkt));
}