mirror of https://github.com/ArduPilot/ardupilot
Add * to the end of flight mode string in CRSF
This commit is contained in:
parent
d85992613b
commit
ad6355c029
|
@ -916,7 +916,13 @@ void AP_CRSF_Telem::calc_flight_mode()
|
||||||
AP_Notify * notify = AP_Notify::get_singleton();
|
AP_Notify * notify = AP_Notify::get_singleton();
|
||||||
if (notify) {
|
if (notify) {
|
||||||
// Note: snprintf() always terminates the string
|
// 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());
|
hal.util->snprintf(
|
||||||
|
_telem.bcast.flightmode.flight_mode,
|
||||||
|
sizeof(AP_CRSF_Telem::FlightModeFrame),
|
||||||
|
"%s%s",
|
||||||
|
notify->get_flight_mode_str(),
|
||||||
|
hal.util->get_soft_armed() ? "" : "*"
|
||||||
|
);
|
||||||
// Note: strlen(_telem.bcast.flightmode.flight_mode) is safe because called on a guaranteed null terminated string
|
// 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_size = strlen(_telem.bcast.flightmode.flight_mode) + 1; //send the terminator as well
|
||||||
_telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_FLIGHT_MODE;
|
_telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_FLIGHT_MODE;
|
||||||
|
|
Loading…
Reference in New Issue