diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 0ddf4fae72..d46df5f3f4 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -415,7 +415,7 @@ void NOINLINE Copter::send_rangefinder(mavlink_channel_t chan) */ void NOINLINE Copter::send_rpm(mavlink_channel_t chan) { - if (rpm_sensor.healthy(0) || rpm_sensor.healthy(1)) { + if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { mavlink_msg_rpm_send( chan, rpm_sensor.get_rpm(0), diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 15d4fdd0c2..9216a79b63 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -75,7 +75,7 @@ int16_t Copter::read_sonar(void) void Copter::rpm_update(void) { rpm_sensor.update(); - if (rpm_sensor.healthy(0) || rpm_sensor.healthy(1)) { + if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { if (should_log(MASK_LOG_RCIN)) { DataFlash.Log_Write_RPM(rpm_sensor); }