From 37f1cce994faf81eb6ba51aaf689dd7f0ebbe1ad Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 8 Oct 2012 17:22:33 +0200 Subject: [PATCH] [fixedwing][feature] AP and FBW on different boards connected via Uart * with example airframe and updated outdated airframes * renamed spi version and make it a separate subsystem (e.g. 2 twogs) closes #297 --- conf/airframes/examples/separate_fbw_ap.xml | 317 ++++++++++++++++ conf/airframes/obsolete/twinjet1.xml | 4 +- conf/airframes/obsolete/twinstar6.xml | 4 +- .../subsystems/fixedwing/autopilot.makefile | 15 +- .../fixedwing/intermcu_spi.makefile | 11 + .../fixedwing/intermcu_uart.makefile | 28 ++ .../shared/actuators_dummy.makefile | 1 + sw/airborne/firmwares/fixedwing/main_ap.c | 6 +- sw/airborne/firmwares/fixedwing/main_fbw.c | 11 +- sw/airborne/{link_mcu.c => link_mcu_spi.c} | 0 sw/airborne/{link_mcu.h => link_mcu_spi.h} | 0 sw/airborne/link_mcu_usart.c | 353 ++++++++++++++++++ sw/airborne/link_mcu_usart.h | 50 +++ 13 files changed, 785 insertions(+), 15 deletions(-) create mode 100644 conf/airframes/examples/separate_fbw_ap.xml create mode 100644 conf/firmwares/subsystems/fixedwing/intermcu_spi.makefile create mode 100644 conf/firmwares/subsystems/fixedwing/intermcu_uart.makefile create mode 100644 conf/firmwares/subsystems/shared/actuators_dummy.makefile rename sw/airborne/{link_mcu.c => link_mcu_spi.c} (100%) rename sw/airborne/{link_mcu.h => link_mcu_spi.h} (100%) create mode 100644 sw/airborne/link_mcu_usart.c create mode 100644 sw/airborne/link_mcu_usart.h diff --git a/conf/airframes/examples/separate_fbw_ap.xml b/conf/airframes/examples/separate_fbw_ap.xml new file mode 100644 index 00000000000..352e060f7c5 --- /dev/null +++ b/conf/airframes/examples/separate_fbw_ap.xml @@ -0,0 +1,317 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + +
+ +
+ + +
+ + + +
+ + +
+ +
+ + + + + +
+ +
+ + + + + + + + + +
+ +
+ + + + + +
+ +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + +
+ + +
+ + + + + + + + +
+ +
+ + + + + + + +
+ +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/airframes/obsolete/twinjet1.xml b/conf/airframes/obsolete/twinjet1.xml index 9442d1e4c10..0c39819c0d5 100644 --- a/conf/airframes/obsolete/twinjet1.xml +++ b/conf/airframes/obsolete/twinjet1.xml @@ -186,7 +186,7 @@ fbw.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLI fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE -fbw.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c +fbw.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c fbw.CFLAGS += -DADC -DUSE_AD0 fbw.srcs += $(SRC_ARCH)/adc_hw.c @@ -202,7 +202,7 @@ ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLIN ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/datalink/pprz_transport.c ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0 -ap.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c +ap.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400 ap.srcs += gps_ubx.c gps.c latlong.c diff --git a/conf/airframes/obsolete/twinstar6.xml b/conf/airframes/obsolete/twinstar6.xml index 347f357bd15..4bbc84a9f53 100644 --- a/conf/airframes/obsolete/twinstar6.xml +++ b/conf/airframes/obsolete/twinstar6.xml @@ -195,7 +195,7 @@ fbw.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLI fbw.srcs += subsystems/datalink/downlink.c subsystems/datalink/pprz_transport.c $(SRC_ARCH)/mcu_periph/uart_arch.c fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE -fbw.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c +fbw.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c fbw.CFLAGS += -DADC -DUSE_AD0 fbw.srcs += $(SRC_ARCH)/adc_hw.c @@ -208,7 +208,7 @@ ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLIN ap.srcs += subsystems/datalink/downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c subsystems/navigation/traffic_info.c subsystems/datalink/pprz_transport.c ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -ap.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c +ap.srcs += inter_mcu.c link_mcu_spi.c spi.c $(SRC_ARCH)/spi_hw.c ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400 ap.srcs += gps_ubx.c gps.c latlong.c diff --git a/conf/firmwares/subsystems/fixedwing/autopilot.makefile b/conf/firmwares/subsystems/fixedwing/autopilot.makefile index 31f1b5a3ed7..b2f26568800 100644 --- a/conf/firmwares/subsystems/fixedwing/autopilot.makefile +++ b/conf/firmwares/subsystems/fixedwing/autopilot.makefile @@ -231,15 +231,16 @@ jsbsim.srcs += $(SRC_ARCH)/subsystems/settings_arch.c # ifeq ($(BOARD),classix) - fbw.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE - fbw.srcs += $(SRC_FIXEDWING)/link_mcu.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c - ap_srcs += $(SRC_FIRMWARE)/fbw_downlink.c - ap.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0 - ap.srcs += $(SRC_FIXEDWING)/link_mcu.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c + include $(CFG_FIXEDWING)/intermcu_spi.makefile else # Single MCU's run both - ap.CFLAGS += $(fbw_CFLAGS) - ap.srcs += $(fbw_srcs) + ifeq ($(SEPARATE_FBW),) + ap.CFLAGS += $(fbw_CFLAGS) + ap.srcs += $(fbw_srcs) + else + # avoid fbw_telemetry_mode error + ap_srcs += $(SRC_FIRMWARE)/fbw_downlink.c + endif endif # diff --git a/conf/firmwares/subsystems/fixedwing/intermcu_spi.makefile b/conf/firmwares/subsystems/fixedwing/intermcu_spi.makefile new file mode 100644 index 00000000000..aad941720c3 --- /dev/null +++ b/conf/firmwares/subsystems/fixedwing/intermcu_spi.makefile @@ -0,0 +1,11 @@ +# Hey Emacs, this is a -*- makefile -*- + +# InterMCU type SPI + + +fbw.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_SLAVE +fbw.srcs += $(SRC_FIXEDWING)/link_mcu_spi.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c +ap_srcs += $(SRC_FIRMWARE)/fbw_downlink.c +ap.CFLAGS += -DMCU_SPI_LINK -DUSE_SPI -DSPI_MASTER -DUSE_SPI_SLAVE0 +ap.srcs += $(SRC_FIXEDWING)/link_mcu_spi.c mcu_periph/spi.c $(SRC_ARCH)/mcu_periph/spi_arch.c +SEPARATE_FBW = 1 diff --git a/conf/firmwares/subsystems/fixedwing/intermcu_uart.makefile b/conf/firmwares/subsystems/fixedwing/intermcu_uart.makefile new file mode 100644 index 00000000000..5ac4dbe84a9 --- /dev/null +++ b/conf/firmwares/subsystems/fixedwing/intermcu_uart.makefile @@ -0,0 +1,28 @@ +# Hey Emacs, this is a -*- makefile -*- + +# InterMCU type UART + + +ifeq ($(TARGET),fbw) + ifeq ($(INTERMCU_PORT),none) + INTERMCU_PORT_NR = 2 + endif + fbw.CFLAGS += -DINTERMCU_LINK=Uart$(INTERMCU_PORT_NR) -DUSE_UART$(INTERMCU_PORT_NR) -DUART$(INTERMCU_PORT_NR)_BAUD=B57600 +else + ifeq ($(INTERMCU_PORT),none) + INTERMCU_PORT_NR = 5 + endif + ap.CFLAGS += -DINTERMCU_LINK=Uart$(INTERMCU_PORT_NR) -DUSE_UART$(INTERMCU_PORT_NR) -DUART$(INTERMCU_PORT_NR)_BAUD=B57600 +endif + +$(TARGET).CFLAGS += -DINTER_MCU -DMCU_UART_LINK +$(TARGET).srcs += ./link_mcu_usart.c + + + + +############################# +# CAN: +# fbw.srcs += ./link_mcu_can.c ./mcu_periph/can.c ./arch/stm32/mcu_periph/can_arch.c +# fbw.CFLAGS += -DINTER_MCU -DMCU_CAN_LINK +# $(TARGET).CFLAGS += -DCAN_SJW_TQ=CAN_SJW_1tq -DCAN_BS1_TQ=CAN_BS1_3tq -DCAN_BS2_TQ=CAN_BS2_4tq -DCAN_PRESCALER=12 -DUSE_CAN -DUSE_CAN1 -DUSE_USB_LP_CAN1_RX0_IRQ -DCAN_ERR_RESUME=DISABLE diff --git a/conf/firmwares/subsystems/shared/actuators_dummy.makefile b/conf/firmwares/subsystems/shared/actuators_dummy.makefile new file mode 100644 index 00000000000..b91bfa8834b --- /dev/null +++ b/conf/firmwares/subsystems/shared/actuators_dummy.makefile @@ -0,0 +1 @@ +# for classix and AP only boards diff --git a/sw/airborne/firmwares/fixedwing/main_ap.c b/sw/airborne/firmwares/fixedwing/main_ap.c index 2cd5481041c..02528f486b1 100644 --- a/sw/airborne/firmwares/fixedwing/main_ap.c +++ b/sw/airborne/firmwares/fixedwing/main_ap.c @@ -191,7 +191,7 @@ void init_ap( void ) { #endif /************* Links initialization ***************/ -#if defined MCU_SPI_LINK +#if defined MCU_SPI_LINK || defined MCU_UART_LINK link_mcu_init(); #endif #if USE_AUDIO_TELEMETRY @@ -540,7 +540,7 @@ void attitude_loop( void ) { ap_state->commands[COMMAND_PITCH] = h_ctl_elevator_setpoint; -#if defined MCU_SPI_LINK +#if defined MCU_SPI_LINK || defined MCU_UART_LINK link_mcu_send(); #elif defined INTER_MCU && defined SINGLE_MCU /**Directly set the flag indicating to FBW that shared buffer is available*/ @@ -633,7 +633,7 @@ void event_task_ap( void ) { DatalinkEvent(); -#ifdef MCU_SPI_LINK +#if defined MCU_SPI_LINK || defined MCU_UART_LINK link_mcu_event_task(); #endif diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 0c7b22060a5..23d7d4f1f60 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -49,6 +49,10 @@ #include "link_mcu.h" #endif +#ifdef MCU_UART_LINK +#include "link_mcu_usart.h" +#endif + uint8_t fbw_mode; #include "inter_mcu.h" @@ -125,7 +129,7 @@ void event_task_fbw( void) { i2c_event(); #ifdef INTER_MCU -#ifdef MCU_SPI_LINK +#if defined MCU_SPI_LINK | defined MCU_UART_LINK link_mcu_event_task(); #endif /* MCU_SPI_LINK */ @@ -204,6 +208,11 @@ void periodic_task_fbw( void ) { } #endif +#ifdef MCU_UART_LINK + inter_mcu_fill_fbw_state(); + link_mcu_periodic_task(); +#endif + #ifdef DOWNLINK fbw_downlink_periodic_task(); #endif diff --git a/sw/airborne/link_mcu.c b/sw/airborne/link_mcu_spi.c similarity index 100% rename from sw/airborne/link_mcu.c rename to sw/airborne/link_mcu_spi.c diff --git a/sw/airborne/link_mcu.h b/sw/airborne/link_mcu_spi.h similarity index 100% rename from sw/airborne/link_mcu.h rename to sw/airborne/link_mcu_spi.h diff --git a/sw/airborne/link_mcu_usart.c b/sw/airborne/link_mcu_usart.c new file mode 100644 index 00000000000..c5a7ff6197d --- /dev/null +++ b/sw/airborne/link_mcu_usart.c @@ -0,0 +1,353 @@ +/* + * Copyright (C) 2010-2012 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#include "link_mcu_usart.h" +#include "mcu_periph/uart.h" +#include "led.h" + +#include "commands.h" + +////////////////////////////////////////////////////////////////////////////////////////////// +// LINK + +#define __InterMcuLink(dev, _x) dev##_x +#define _InterMcuLink(dev, _x) __InterMcuLink(dev, _x) +#define InterMcuLink(_x) _InterMcuLink(INTERMCU_LINK, _x) + +#define InterMcuBuffer() InterMcuLink(ChAvailable()) + +#define InterMcuUartSend1(c) InterMcuLink(Transmit(c)) +#define InterMcuUartSetBaudrate(_a) InterMcuLink(SetBaudrate(_a)) +#define InterMcuUartRunning InterMcuLink(TxRunning) +#define InterMcuUartSendMessage InterMcuLink(SendMessage) + +////////////////////////////////////////////////////////////////////////////////////////////// +// PROTOCOL + +#define INTERMCU_SYNC1 0xB5 +#define INTERMCU_SYNC2 0x62 + +#define InterMcuInitCheksum() { intermcu_data.send_ck_a = intermcu_data.send_ck_b = 0; } +#define UpdateChecksum(c) { intermcu_data.send_ck_a += c; intermcu_data.send_ck_b += intermcu_data.send_ck_a; } +#define InterMcuTrailer() { InterMcuUartSend1(intermcu_data.send_ck_a); InterMcuUartSend1(intermcu_data.send_ck_b); InterMcuUartSendMessage(); } + +#define InterMcuSend1(c) { uint8_t i8=c; InterMcuUartSend1(i8); UpdateChecksum(i8); } +#define InterMcuSend2(c) { uint16_t i16=c; InterMcuSend1(i16&0xff); InterMcuSend1(i16 >> 8); } +#define InterMcuSend1ByAddr(x) { InterMcuSend1(*x); } +#define InterMcuSend2ByAddr(x) { InterMcuSend1(*x); InterMcuSend1(*(x+1)); } +#define InterMcuSend4ByAddr(x) { InterMcuSend1(*x); InterMcuSend1(*(x+1)); InterMcuSend1(*(x+2)); InterMcuSend1(*(x+3)); } + +#define InterMcuHeader(nav_id, msg_id, len) { \ + InterMcuUartSend1(INTERMCU_SYNC1); \ + InterMcuUartSend1(INTERMCU_SYNC2); \ + InterMcuInitCheksum(); \ + InterMcuSend1(nav_id); \ + InterMcuSend1(msg_id); \ + InterMcuSend2(len); \ + } + +////////////////////////////////////////////////////////////////////////////////////////////// +// MESSAGES + +// class +#define MSG_INTERMCU_ID 100 + + +#define MSG_INTERMCU_COMMAND_ID 0x05 +#define MSG_INTERMCU_COMMAND_LENGTH (2*(COMMANDS_NB)) +#define MSG_INTERMCU_COMMAND(_intermcu_payload, nr) (uint16_t)(*((uint8_t*)_intermcu_payload+0)|*((uint8_t*)_intermcu_payload+1+(2*(nr)))<<8) + +#define InterMcuSend_INTERMCU_COMMAND(cmd) { \ + InterMcuHeader(MSG_INTERMCU_ID, MSG_INTERMCU_COMMAND_ID, MSG_INTERMCU_COMMAND_LENGTH);\ + for (int i=0;i INTERMCU_MAX_PAYLOAD) { + goto error; + } + intermcu_data.msg_idx = 0; + intermcu_data.status++; + break; + case GOT_LEN2: + intermcu_data.msg_buf[intermcu_data.msg_idx] = c; + intermcu_data.msg_idx++; + if (intermcu_data.msg_idx >= intermcu_data.len) { + intermcu_data.status++; + } + break; + case GOT_PAYLOAD: + if (c != intermcu_data.ck_a) { + goto error; + } + intermcu_data.status++; + break; + case GOT_CHECKSUM1: + if (c != intermcu_data.ck_b) { + goto error; + } + intermcu_data.msg_available = TRUE; + goto restart; + break; + default: + goto error; + } + return; + error: + intermcu_data.error_cnt++; + restart: + intermcu_data.status = UNINIT; + return; +} + + + +////////////////////////////////////////////////////////////////////////////////////////////// +// USER + + +struct link_mcu_msg link_mcu_from_ap_msg; +struct link_mcu_msg link_mcu_from_fbw_msg; + +inline void parse_mavpilot_msg( void ); + +void link_mcu_init( void ) +{ + intermcu_data.status = UNINIT; + intermcu_data.msg_available = FALSE; + intermcu_data.error_cnt = 0; +} + +void parse_mavpilot_msg( void ) +{ + if (intermcu_data.msg_class == MSG_INTERMCU_ID) + { + if (intermcu_data.msg_id == MSG_INTERMCU_COMMAND_ID) + { +#if COMMANDS_NB > 8 +#error "INTERMCU UART CAN ONLY SEND 8 COMMANDS OR THE UART WILL BE OVERFILLED" +#endif + + for (int i=0; i< COMMANDS_NB; i++) + { + ap_state->commands[i] = ((pprz_t)MSG_INTERMCU_COMMAND(intermcu_data.msg_buf, i)); + } + +#ifdef LINK_MCU_LED + LED_TOGGLE(LINK_MCU_LED); +#endif + inter_mcu_received_ap = TRUE; + } + else if (intermcu_data.msg_id == MSG_INTERMCU_RADIO_ID) + { +#if RADIO_CONTROL_NB_CHANNEL > 10 +#error "INTERMCU UART CAN ONLY SEND 10 RADIO CHANNELS OR THE UART WILL BE OVERFILLED" +#endif + + for (int i=0; i< RADIO_CONTROL_NB_CHANNEL; i++) + { + fbw_state->channels[i] = ((pprz_t)MSG_INTERMCU_RADIO(intermcu_data.msg_buf, i)); + } + } + else if (intermcu_data.msg_id == MSG_INTERMCU_TRIM_ID) + { + ap_state->command_roll_trim = ((pprz_t) MSG_INTERMCU_TRIM_ROLL(intermcu_data.msg_buf)); + ap_state->command_pitch_trim = ((pprz_t) MSG_INTERMCU_TRIM_PITCH(intermcu_data.msg_buf)); + } + else if (intermcu_data.msg_id == MSG_INTERMCU_FBW_ID) + { + fbw_state->ppm_cpt = MSG_INTERMCU_FBW_MOD(intermcu_data.msg_buf); + fbw_state->status = MSG_INTERMCU_FBW_STAT(intermcu_data.msg_buf); + fbw_state->nb_err = MSG_INTERMCU_FBW_ERR(intermcu_data.msg_buf); + fbw_state->vsupply = MSG_INTERMCU_FBW_VOLT(intermcu_data.msg_buf); + fbw_state->current = MSG_INTERMCU_FBW_CURRENT(intermcu_data.msg_buf); + + inter_mcu_received_fbw = TRUE; + } + } +} + + +#ifdef AP +void link_mcu_send( void ) +{ +#ifdef LINK_MCU_LED + LED_TOGGLE(LINK_MCU_LED); +#endif + InterMcuSend_INTERMCU_COMMAND( ap_state->commands ); + InterMcuSend_INTERMCU_TRIM( ap_state->command_roll_trim, ap_state->command_pitch_trim ); +} +#endif + +#ifdef FBW +// 60 Hz +static uint8_t SixtyHzCounter = 0; + +void link_mcu_periodic_task( void ) +{ + SixtyHzCounter++; + if (SixtyHzCounter >= 3) + { + // 20 Hz + SixtyHzCounter = 0; + inter_mcu_fill_fbw_state(); /** Prepares the next message for AP */ + + InterMcuSend_INTERMCU_FBW( + fbw_state->ppm_cpt, + fbw_state->status, + fbw_state->nb_err, + fbw_state->vsupply, + fbw_state->current); +#if defined RADIO_CONTROL || RADIO_CONTROL_AUTO1 + InterMcuSend_INTERMCU_RADIO( fbw_state->channels ); +#endif + + } +} +#endif + +void link_mcu_event_task( void ) { + /* A message has been received */ + if (InterMcuBuffer()) { + while (InterMcuLink(ChAvailable())&&!intermcu_data.msg_available) + intermcu_parse(InterMcuLink(Getch())); + } + + if (intermcu_data.msg_available) { + parse_mavpilot_msg(); + intermcu_data.msg_available = FALSE; + } +} diff --git a/sw/airborne/link_mcu_usart.h b/sw/airborne/link_mcu_usart.h new file mode 100644 index 00000000000..775ef90008e --- /dev/null +++ b/sw/airborne/link_mcu_usart.h @@ -0,0 +1,50 @@ +/* + * Copyright (C) 2010-2012 The Paparazzi Team + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \brief Transport for the communication between FBW and AP via UART. + */ + +#ifndef LINK_MCU_H +#define LINK_MCU_H + +#include +#include "inter_mcu.h" + +struct link_mcu_msg { + union { + struct fbw_state from_fbw; + struct ap_state from_ap; + } payload; +}; + +extern struct link_mcu_msg link_mcu_from_ap_msg; +extern struct link_mcu_msg link_mcu_from_fbw_msg; + +extern bool_t link_mcu_received; + +extern void link_mcu_send( void ); +extern void link_mcu_init( void ); +extern void link_mcu_event_task( void ); +extern void link_mcu_periodic_task( void ); + + +#endif