/* * populate and send MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG */ void AP_ADSB::send_configure(const mavlink_channel_t chan) { // MAVLink spec says the 9 byte callsign field is 8 byte string with 9th byte as null. // Here we temporarily set some flags in that null char to signify the callsign // may be a flightplanID instead int8_t callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN]; uint32_t icao; memcpy(callsign, out_state.cfg.callsign, sizeof(out_state.cfg.callsign)); if (out_state.cfg.was_set_externally) { // take values as-is icao = out_state.cfg.ICAO_id; } else { callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = (int8_t)get_encoded_callsign_null_char(); icao = get_encoded_icao(); } mavlink_msg_uavionix_adsb_out_cfg_send( chan, icao, (const char*)callsign, (uint8_t)out_state.cfg.emitterType, (uint8_t)out_state.cfg.lengthWidth, (uint8_t)out_state.cfg.gpsLatOffset, (uint8_t)out_state.cfg.gpsLonOffset, out_state.cfg.stall_speed_cm, (uint8_t)out_state.cfg.rfSelect); }
void AP_ADSB::send_configure(const mavlink_channel_t chan) { mavlink_msg_uavionix_adsb_out_cfg_send( chan, (uint32_t)out_state.cfg.ICAO_id, out_state.cfg.callsign, (uint8_t)out_state.cfg.emitterType, (uint8_t)out_state.cfg.lengthWidth, (uint8_t)out_state.cfg.gpsLatOffset, (uint8_t)out_state.cfg.gpsLonOffset, out_state.cfg.stall_speed_cm, (uint8_t)out_state.cfg.rfSelect); }