/* UART instance and clock */
#define DEMO_UART UART2
#define DEMO_UART_CLKSRC UART2_CLK_SRC
#define DEMO_UART_CLK_FREQ CLOCK_GetFreq(UART2_CLK_SRC)
#define DEMO_UART_IRQn UART2_RX_TX_IRQn
#define DEMO_UART_IRQHandler UART2_RX_TX_IRQHandler/* Initialize UART2 */
uart_config_t config;
UART_GetDefaultConfig(&config);
config.baudRate_Bps = BOARD_DEBUG_UART_BAUDRATE;
config.enableTx = true;
config.enableRx = true;
UART_Init(DEMO_UART, &config, DEMO_UART_CLK_FREQ);#include "../mavlink/common/mavlink.h"uint32_t tx_custom_mode = 0xffff; /*< A bitfield for use for autopilot-specific flags*/
uint8_t tx_type = MAV_TYPE_QUADROTOR; /*< Type of the system (quadrotor, helicopter, etc.).*/
uint8_t tx_autopilot = MAV_AUTOPILOT_PX4; /*< Autopilot type / class.*/
uint8_t tx_base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED; /*< System mode bitmap.*/
uint8_t tx_system_status = MAV_STATE_ACTIVE; /*< System status flag.*/
/* create mavlink heartbeat message and send over UART */
mavlink_msg_heartbeat_pack(1, 200, &tx_mav_msg, tx_type, tx_autopilot,
tx_base_mode, tx_custom_mode, tx_system_status);
len_mav = mavlink_msg_to_send_buffer(send_mav_buffer, &tx_mav_msg);
UART_WriteBlocking(DEMO_UART, send_mav_buffer, len_mav);/* receiving a message via UART*/
while ((kUART_TxDataRegEmptyFlag & UART_GetStatusFlags(DEMO_UART))
&& (rxIndex != txIndex)) {
msgReceived = mavlink_parse_char(MAVLINK_COMM_1,
demoRingBuffer[txIndex], &message, &status);
txIndex++;
txIndex %= DEMO_RING_BUFFER_SIZE;
}mavlink_sys_status_t sys_status;
mavlink_msg_sys_status_decode(&message, &sys_status);
sprintf(buff, "Voltage = %.2f V", (float)(sys_status.voltage_battery)/1000);
GUI_DispStringHCenterAt(buff, 88, 66);
















