mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
Copter: Always send RPM data when sensor is enabled
This commit is contained in:
parent
a08fa50fda
commit
9848d05a9d
@ -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),
|
||||
|
@ -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);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user