diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 83c55ca596..508ae31959 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -817,9 +817,10 @@ void AP_CRSF_Telem::calc_flight_mode() { AP_Notify * notify = AP_Notify::get_singleton(); if (notify) { - hal.util->snprintf(_telem.bcast.flightmode.flight_mode, 16, "%s", notify->get_flight_mode_str()); - - _telem_size = sizeof(AP_CRSF_Telem::FlightModeFrame); + // Note: snprintf() always terminates the string + hal.util->snprintf(_telem.bcast.flightmode.flight_mode, sizeof(AP_CRSF_Telem::FlightModeFrame), "%s", notify->get_flight_mode_str()); + // Note: strlen(_telem.bcast.flightmode.flight_mode) is safe because called on a guaranteed null terminated string + _telem_size = strlen(_telem.bcast.flightmode.flight_mode) + 1; //send the terminator as well _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_FLIGHT_MODE; _telem_pending = true; }