Browse Source

Force RSSI to zero if RC is lost

sbg
Lorenz Meier 10 years ago
parent
commit
412ddde5dc
  1. 5
      src/modules/mavlink/mavlink_messages.cpp

5
src/modules/mavlink/mavlink_messages.cpp

@ -1760,6 +1760,11 @@ protected: @@ -1760,6 +1760,11 @@ protected:
break;
}
if (rc.rc_lost) {
/* RSSI is by definition zero */
msg.rssi = 0;
}
_mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS, &msg);
}
}

Loading…
Cancel
Save