diff --git a/Makefile b/Makefile index 261eb58a88..ebb8b26434 100644 --- a/Makefile +++ b/Makefile @@ -54,7 +54,7 @@ conf/%.xml :conf/%.xml.example [ -L $@ ] || [ -f $@ ] || cp $< $@ -test: static ac1 ac2 +demo: static ac1 ac2 PAPARAZZI_HOME=$(PAPARAZZI_SRC) PAPARAZZI_SRC=$(PAPARAZZI_SRC) $(SUPERVISION) ac1 : conf sim_static @@ -81,6 +81,9 @@ sim_static : fbw fly_by_wire: ac_h cd $(AIRBORNE); $(MAKE) TARGET=fbw all +%.compile: ac_h + cd $(AIRBORNE); $(MAKE) TARGET=$* all + ap autopilot: ac_h cd $(AIRBORNE); $(MAKE) TARGET=ap all @@ -90,6 +93,9 @@ sim: ac_h sim_static upload_fbw: fbw cd $(AIRBORNE); $(MAKE) TARGET=fbw upload +%.upload: %.compile + cd $(AIRBORNE); $(MAKE) TARGET=$* upload + upload_ap: ap cd $(AIRBORNE); $(MAKE) TARGET=ap upload diff --git a/conf/Makefile.arm7 b/conf/Makefile.arm7 index 27c77bdcf6..ba4c5d2f1b 100644 --- a/conf/Makefile.arm7 +++ b/conf/Makefile.arm7 @@ -188,7 +188,8 @@ LPC21ISP_FLASHFILE = $(OBJDIR)/$(TARGET).hex #LPC21ISP_DEBUG = -debug # enter bootloader via RS232 DTR/RTS (only if hardware supports this # feature - see Philips AppNote): -LPC21ISP_CONTROL = -control +LPC21ISP_CONTROL = +# -control # --------------------------------------------------------------------------- diff --git a/conf/airframes/twinjet1.xml b/conf/airframes/twinjet1.xml index 76ed043ce5..aeaae64a73 100644 --- a/conf/airframes/twinjet1.xml +++ b/conf/airframes/twinjet1.xml @@ -1,107 +1,161 @@ - - + - - - + + - - - + + + - - + +
- - + +
- - - - - + + + + + -
- - + + +
- - - - - - - - - - + + + + + + + + + +
- + +
+ + + + + + + +
+
- - - - + + + + - - - + + +
+
- - + +
- - -
- - - - - - - - -
- -
- - - + +
+ + + + +
+
- +
+ +
+ + + +
- -include $(PAPARAZZI_SRC)/conf/autopilot/robostix.makefile +
+ + + + + +
-ap.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -ap.srcs += pprz_transport.c downlink.c + +include $(PAPARAZZI_SRC)/conf/autopilot/classix.makefile -ap.CFLAGS += -DUSE_UART0 -DDOWNLINK_AP_DEVICE=Uart0 -DDOWNLINK_FBW_DEVICE=Uart0 -ap.srcs += $(SRC_ARCH)/uart_hw.c +fbw.CFLAGS += -DFBW -DCONFIG=\"classix.h\" -DLED -DTIME_LED=1 +fbw.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main.c + +fbw.srcs += commands.c + +fbw.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -DSERVOS_4017_CLOCK_FALLING +fbw.srcs += $(SRC_ARCH)/servos_4017_hw.c + +fbw.CFLAGS += -DRADIO_CONTROL -DRADIO_CONTROL_TYPE=RC_FUTABA +fbw.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c + +fbw.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 +fbw.srcs += downlink.c pprz_transport.c $(SRC_ARCH)/uart_hw.c + +fbw.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK +fbw.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c + +fbw.CFLAGS += -DADC -DUSE_AD0_6 +fbw.srcs += $(SRC_ARCH)/adc_hw.c +ap.CFLAGS += -DAP -DCONFIG=\"classix.h\" -DLED -DTIME_LED=2 +ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_ap.c main.c + +ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_AP_DEVICE=Uart0 +ap.srcs += downlink.c pprz_transport.c $(SRC_ARCH)/uart_hw.c + +ap.CFLAGS += -DINTER_MCU -DMCU_SPI_LINK +ap.srcs += inter_mcu.c link_mcu.c spi.c $(SRC_ARCH)/spi_hw.c + +ap.CFLAGS += -DGPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 +ap.srcs += gps_ubx.c gps.c + +ap.CFLAGS += -DADC -DUSE_AD0_1 -DUSE_AD0_2 -DUSE_AD0_3 +ap.srcs += $(SRC_ARCH)/adc_hw.c + +ap.CFLAGS += -DINFRARED +ap.srcs += infrared.c estimator.c + +ap.srcs += nav.c pid.c + + + +test.CFLAGS += -DFBW -DCONFIG=\"classix.h\" -DLED -DTIME_LED=1 -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -DSERVOS_4017_CLOCK_FALLING -DUSE_UART0 -DDATALINK -DPPRZ_INPUT -DPPRZ_UART=Uart0 +test.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c setup_actuators.c $(SRC_ARCH)/uart_hw.c $(SRC_ARCH)/servos_4017_hw.c main.c + + diff --git a/conf/airframes/twinstar1.xml b/conf/airframes/twinstar1.xml index d10199b8cf..b7228f7596 100644 --- a/conf/airframes/twinstar1.xml +++ b/conf/airframes/twinstar1.xml @@ -121,7 +121,7 @@ ap.EXTRA_SRCS += pprz_transport.c downlink.c # Datalink (on uart0) used to emulate sensors (infrared and gps) ap.EXTRA_SRCS += traffic_info.c datalink.c -ap.CFLAGS += -DDATALINK -DPPRZ_INPUT +ap.CFLAGS += -DDATALINK -DPPRZ_INPUT -DPPRZ_UART=Uart0 # Config for SITL simulation include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile diff --git a/conf/airframes/twinstar4.xml b/conf/airframes/twinstar4.xml index ed8a20b21f..934995e9e4 100755 --- a/conf/airframes/twinstar4.xml +++ b/conf/airframes/twinstar4.xml @@ -129,7 +129,7 @@ ap.srcs += if_calib.c ap.CFLAGS += -DDATALINK ap.srcs += traffic_info.c datalink.c -ap.CFLAGS += -DWAVECARD -DUSE_UART0 +ap.CFLAGS += -DWAVECARD -DWAVECARD_UART=Uart0 -DUSE_UART0 ap.srcs += wavecard.c
diff --git a/conf/autopilot/classix.h b/conf/autopilot/classix.h index 7bc68f564a..4d58b1fe50 100644 --- a/conf/autopilot/classix.h +++ b/conf/autopilot/classix.h @@ -46,8 +46,7 @@ //#define SERVO_RESET_PINSEL_BIT 3 /* ADCs : supply on AD0.6 ( P0.4 ) */ -#define USE_AD0_6 -#define BRICOLAGE_ADC +//#define USE_AD0_6 #endif /* FBW */ diff --git a/conf/autopilot/classix.makefile b/conf/autopilot/classix.makefile index 666f049828..7765ed9a61 100644 --- a/conf/autopilot/classix.makefile +++ b/conf/autopilot/classix.makefile @@ -13,5 +13,10 @@ fbw.ARCH = arm7tdmi fbw.TARGET = fbw fbw.TARGETDIR = fbw +test.ARCHDIR = $(ARCHI) +test.ARCH = arm7tdmi +test.TARGET = fbw +test.TARGETDIR = fbw + LPC21ISP_BAUD = 38400 -LPC21ISP_XTAL = 12000 \ No newline at end of file +LPC21ISP_XTAL = 12000 diff --git a/conf/messages.xml b/conf/messages.xml index 6ec52815ae..e62e766beb 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -250,6 +250,7 @@ + @@ -303,6 +304,11 @@ + + + + + diff --git a/conf/telemetry/default.xml b/conf/telemetry/default.xml index 8b27cb9c0f..01fdbc5e55 100644 --- a/conf/telemetry/default.xml +++ b/conf/telemetry/default.xml @@ -29,11 +29,8 @@ - - - diff --git a/sw/airborne/arm7/adc_hw.c b/sw/airborne/arm7/adc_hw.c index 7efcb92f07..409d7900cc 100644 --- a/sw/airborne/arm7/adc_hw.c +++ b/sw/airborne/arm7/adc_hw.c @@ -152,12 +152,12 @@ void adc_init( void ) { /* connect pins for selected ADCs */ /* if I configure both PINSEL0 and 1 it crashes even with PINSEL0 |= 0 !!!!!!! */ - // PINSEL0 |= ADC_PINSEL0_ONES; + PINSEL0 |= ADC_PINSEL0_ONES; // PINSEL0 |= 0; PINSEL1 |= ADC_PINSEL1_ONES; /* setup hw scan - PCLK/7 ( 4.3MHz) - BURST ON */ - AD0CR = ADC_AD0CR_SEL_HW_SCAN | 0x06 << 8 | 1 << 16 | 0x01 << 21 ; + AD0CR = ADC_AD0CR_SEL_HW_SCAN | 0xFF << 8 | 1 << 16 | 0x01 << 21 ; /* AD0 selected as IRQ */ VICIntSelect &= ~VIC_BIT(VIC_AD0); /* AD0 interrupt enabled */ @@ -173,34 +173,31 @@ void adc_init( void ) { void adcISR0 ( void ) { ISR_ENTRY(); - LED_ON(1); uint32_t tmp = AD0DR; uint8_t channel = (uint8_t)(tmp >> 24) & 0x07; uint16_t value = (uint16_t)(tmp >> 6) & 0x03FF; adc0_val[channel] = value; - // LED_TOGGLE(2); - /* + struct adc_buf* buf = buffers[channel]; if (buf) { uint8_t new_head = buf->head + 1; if (new_head >= buf->av_nb_sample) new_head = 0; buf->sum -= buf->values[new_head]; - buf->values[new_head] = adc_value; - buf->sum += adc_value; + buf->values[new_head] = value; + buf->sum += value; buf->head = new_head; } - */ - LED_OFF(1); + VICVectAddr = 0x00000000; // clear this interrupt from the VIC ISR_EXIT(); // recover registers and return } -void adcISR1 ( void ) { - ISR_ENTRY(); - uint32_t tmp = AD1DR; - uint8_t channel = (uint8_t)(tmp >> 24) & 0x07; - adc1_val[channel] = (uint16_t)(tmp >> 6) & 0x03FF; - // LED_TOGGLE(1); - VICVectAddr = 0x00000000; // clear this interrupt from the VIC - ISR_EXIT(); // recover registers and return -} +/* void adcISR1 ( void ) { */ +/* ISR_ENTRY(); */ +/* uint32_t tmp = AD1DR; */ +/* uint8_t channel = (uint8_t)(tmp >> 24) & 0x07; */ +/* adc1_val[channel] = (uint16_t)(tmp >> 6) & 0x03FF; */ +/* // LED_TOGGLE(1); */ +/* VICVectAddr = 0x00000000; // clear this interrupt from the VIC */ +/* ISR_EXIT(); // recover registers and return */ +/* } */ diff --git a/sw/airborne/arm7/spi_hw.c b/sw/airborne/arm7/spi_hw.c index 6499c65174..27ea0093a4 100644 --- a/sw/airborne/arm7/spi_hw.c +++ b/sw/airborne/arm7/spi_hw.c @@ -46,7 +46,7 @@ void SPI1_ISR(void) __attribute__((naked)); /* SSPCR1 settings */ #define SSP_LBM 0x00 << 0 /* loopback mode : disabled */ -#define SSP_SSE 0x01 << 0 /* SSP enable : disabled */ +#define SSP_SSE 0x00 << 1 /* SSP enable : disabled */ #define SSP_MS 0x01 << 2 /* master slave mode : slave */ #define SSP_SOD 0x00 << 3 /* slave output disable : disabled */ @@ -74,7 +74,7 @@ void spi_init( void ) { VICVectAddr7 = (uint32_t)SPI1_ISR; // address of the ISR /* enable SPI */ - SpiEnable(); + // SpiEnable(); } void SPI1_ISR(void) { @@ -92,6 +92,7 @@ void SPI1_ISR(void) { SpiReceive(); SpiClearRti(); /* clear interrupt */ SpiDisableRti(); + SpiDisable(); spi_message_received = TRUE; } @@ -127,7 +128,7 @@ void SPI1_ISR(void) __attribute__((naked)); /* SSPCR1 settings */ #define SSP_LBM 0x00 << 0 /* loopback mode : disabled */ -#define SSP_SSE 0x01 << 0 /* SSP enable : disabled */ +#define SSP_SSE 0x00 << 1 /* SSP enable : disabled */ #define SSP_MS 0x00 << 2 /* master slave mode : master */ #define SSP_SOD 0x00 << 3 /* slave output disable : don't care when master */ @@ -147,7 +148,7 @@ void spi_init( void ) { /* setup SSP */ SSPCR0 = SSP_DDS | SSP_FRF | SSP_CPOL | SSP_CPHA | SSP_SCR; - SSPCR1 = SSP_LBM | SSP_SSE | SSP_MS | SSP_SOD; + SSPCR1 = SSP_LBM | SSP_MS | SSP_SOD; SSPCPSR = 0x20; /* initialize interrupt vector */ @@ -175,6 +176,7 @@ void SPI1_ISR(void) { SpiDisableRti(); SpiClearRti(); /* clear interrupt */ SpiDisable(); + spi_message_received = TRUE; } // SPI_UNSELECT_SLAVE1(); /* debug */ diff --git a/sw/airborne/arm7/spi_hw.h b/sw/airborne/arm7/spi_hw.h index a741a0cf49..1419f8b708 100644 --- a/sw/airborne/arm7/spi_hw.h +++ b/sw/airborne/arm7/spi_hw.h @@ -105,13 +105,14 @@ extern volatile uint8_t spi_rx_idx; } #define SpiRead(a) { \ - a = SSPDR; \ + a = SSPDR; \ } #ifdef FBW #define SpiStart() { \ - SpiInitBuf(); \ - SpiEnableTxi(); /* enable tx fifo half empty interrupt */ \ + SpiEnable(); \ + SpiInitBuf(); \ + SpiEnableTxi(); /* enable tx fifo half empty interrupt */ \ } #endif /* FBW */ diff --git a/sw/airborne/arm7/uart_hw.h b/sw/airborne/arm7/uart_hw.h index 43dd9b63e9..afef90e91a 100644 --- a/sw/airborne/arm7/uart_hw.h +++ b/sw/airborne/arm7/uart_hw.h @@ -39,6 +39,18 @@ #define UART_FIFO_14 (uint8_t)(UFCR_FIFO_ENABLE + UFCR_FIFO_TRIG14) +extern uint16_t uart0_rx_insert_idx, uart0_rx_extract_idx; +extern uint8_t uart0_rx_buffer[UART0_RX_BUFFER_SIZE]; + +#define Uart0ChAvailable() (uart0_rx_insert_idx != uart0_rx_extract_idx) + +#define Uart0Getch() ({\ + uint8_t ret = uart0_rx_buffer[uart0_rx_extract_idx]; \ + uart0_rx_extract_idx = (uart0_rx_extract_idx + 1)%UART0_RX_BUFFER_SIZE; \ + ret; \ +}) + + extern uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx; extern uint8_t uart1_rx_buffer[UART0_RX_BUFFER_SIZE]; diff --git a/sw/airborne/avr/uart_hw.c b/sw/airborne/avr/uart_hw.c index f9049b5434..967710c023 100644 --- a/sw/airborne/avr/uart_hw.c +++ b/sw/airborne/avr/uart_hw.c @@ -168,6 +168,14 @@ SIGNAL(SIG_UART0_TRANS) { } } +uint8_t uart0_char; +bool_t uart0_char_available; + +SIGNAL( SIG_UART0_RECV ) { + uart0_char = UDR0; + uart0_char_available = TRUE; +} + void uart1_init_tx( void ) { /* Baudrate is 38.4k */ diff --git a/sw/airborne/avr/uart_hw.h b/sw/airborne/avr/uart_hw.h index 44dea0b170..fb236bc2c4 100644 --- a/sw/airborne/avr/uart_hw.h +++ b/sw/airborne/avr/uart_hw.h @@ -53,17 +53,6 @@ /************************************************************************/ #if defined (__AVR_ATmega128__) -#define ReceiveUart0(cb) \ - SIGNAL( SIG_UART0_RECV ) { \ - uint8_t c = UDR0; \ - cb(c); \ -} -#define ReceiveUart1(cb) \ - SIGNAL( SIG_UART1_RECV ) { \ - uint8_t c = UDR1; \ - cb(c); \ -} - extern uint8_t tx_buf0[256]; /** For debugging purpose */ extern void uart0_init_tx(void); @@ -73,10 +62,17 @@ extern void uart1_init(void); extern void uart0_transmit(const uint8_t); extern void uart1_transmit(const uint8_t); -extern uint8_t uart1_char; -extern bool_t uart1_char_available; +extern uint8_t uart1_char, uart0_char; +extern bool_t uart1_char_available, uart0_char_available; +#define Uart0ChAvailable() (uart0_char_available) #define Uart1ChAvailable() (uart1_char_available) + +static inline uint8_t Uart0Getch( void ) { + uart0_char_available = FALSE; + return uart0_char; +} + static inline uint8_t Uart1Getch( void ) { uart1_char_available = FALSE; return uart1_char; diff --git a/sw/airborne/datalink.c b/sw/airborne/datalink.c index 206a8443c8..a37adf696e 100644 --- a/sw/airborne/datalink.c +++ b/sw/airborne/datalink.c @@ -28,7 +28,6 @@ #define DATALINK_C #include -#include "dl_protocol.h" #include "traffic_info.h" #include "nav.h" #include "datalink.h" diff --git a/sw/airborne/datalink.h b/sw/airborne/datalink.h index 1a8e012de7..4ab65da38c 100644 --- a/sw/airborne/datalink.h +++ b/sw/airborne/datalink.h @@ -35,6 +35,8 @@ #define EXTERN extern #endif +#include "dl_protocol.h" + EXTERN bool_t dl_msg_available; /** Flag provided to control calls to ::dl_parse_msg. NOT used in this module*/ diff --git a/sw/airborne/fbw_downlink.h b/sw/airborne/fbw_downlink.h index 9048956c95..6dde3f17ef 100644 --- a/sw/airborne/fbw_downlink.h +++ b/sw/airborne/fbw_downlink.h @@ -42,7 +42,7 @@ extern uint8_t telemetry_mode_Fbw; #define PERIODIC_SEND_PPM() DOWNLINK_SEND_PPM(PPM_NB_PULSES, ppm_pulses) #define PERIODIC_SEND_RC() DOWNLINK_SEND_RC(PPM_NB_PULSES, rc_values) #define PERIODIC_SEND_COMMANDS() DOWNLINK_SEND_COMMANDS(COMMANDS_NB, commands) -#define PERIODIC_SEND_FBW_STATUS() DOWNLINK_SEND_FBW_STATUS(&fbw_state->nb_err, &rc_status, &fbw_mode) +#define PERIODIC_SEND_FBW_STATUS() DOWNLINK_SEND_FBW_STATUS(&fbw_state->nb_err, &rc_status, &fbw_mode, &fbw_vsupply_decivolt) #ifdef BRICOLAGE_ADC extern uint16_t adc0_val[]; diff --git a/sw/airborne/inter_mcu.h b/sw/airborne/inter_mcu.h index f667f9642d..148aeacd69 100644 --- a/sw/airborne/inter_mcu.h +++ b/sw/airborne/inter_mcu.h @@ -108,6 +108,12 @@ static inline void inter_mcu_fill_fbw_state (void) { } fbw_state->vsupply = fbw_vsupply_decivolt; + /** + for(i = 0; i < sizeof(*fbw_state); i++) { + ((uint8_t*)fbw_state)[i] = i; + } + **/ + } /** Prepares date for next comm with AP. Set ::ap_ok to TRUE */ diff --git a/sw/airborne/main_ap.c b/sw/airborne/main_ap.c index 99297a4145..0edf68aa81 100644 --- a/sw/airborne/main_ap.c +++ b/sw/airborne/main_ap.c @@ -541,9 +541,7 @@ void init_ap( void ) { if (sys_time_periodic()) init_cpt--; } - uart0_transmit(42); wc_configure(); - DOWNLINK_SEND_DEBUG2(16, tx_buf0); #endif } @@ -567,17 +565,22 @@ void event_task_ap( void ) { #endif /** GPS */ #ifdef WAVECARD - if (wc_msg_received) { - DOWNLINK_SEND_DEBUG1(10, wc_payload); - wc_parse_payload(); - wc_msg_received = FALSE; + if (WavecardBuffer()) { + ReadWavecardBuffer(); + if (wc_msg_received) { + wc_parse_payload(); + wc_msg_received = FALSE; + } } #endif /** WAVECARD */ #ifdef PPRZ_INPUT - if (pprz_msg_received) { - pprz_msg_received = FALSE; - pprz_parse_payload(); + if (PprzBuffer()) { + ReadPprzBuffer(); + if (pprz_msg_received) { + pprz_msg_received = FALSE; + pprz_parse_payload(); + } } #endif /** PPRZ_INPUT */ @@ -604,6 +607,7 @@ void event_task_ap( void ) { #ifdef MCU_SPI_LINK if (spi_message_received) { /* Got a message on SPI. */ + DOWNLINK_SEND_DEBUG1((uint8_t)sizeof(link_mcu_from_fbw_msg), ((uint8_t*)&(link_mcu_from_fbw_msg))); spi_message_received = FALSE; link_mcu_event_task(); } diff --git a/sw/airborne/main_ap_2.c b/sw/airborne/main_ap_2.c index 10563ff772..4eeadca3d3 100644 --- a/sw/airborne/main_ap_2.c +++ b/sw/airborne/main_ap_2.c @@ -18,8 +18,12 @@ #include "infrared.h" #include "estimator.h" +#include "nav.h" #include "airframe.h" +float pitch_of_vz; +float pitch_of_vz_pgain; +bool_t auto_pitch = FALSE; uint8_t ac_ident = AC_ID; float desired_roll = 0.; float desired_pitch = 0.; @@ -34,9 +38,9 @@ uint8_t horizontal_mode; uint8_t inflight_calib_mode; uint8_t mcu1_status; uint8_t ir_estim_mode; -int32_t nav_utm_east0; -int32_t nav_utm_north0; -int8_t nav_utm_zone0; +//int32_t nav_utm_east0; +//int32_t nav_utm_north0; +//int8_t nav_utm_zone0; //float estimator_phi; //float estimator_psi; //float estimator_theta; @@ -47,24 +51,24 @@ int8_t nav_utm_zone0; //float estimator_hspeed_dir; //float estimator_z_dot; //uint16_t estimator_flight_time; -bool_t in_segment; -int16_t segment_x_1; -int16_t segment_y_1; -int16_t segment_x_2; -int16_t segment_y_2; +//bool_t in_segment; +//int16_t segment_x_1; +//int16_t segment_y_1; +//int16_t segment_x_2; +//int16_t segment_y_2; float energy; int16_t desired_gaz; uint8_t vsupply; bool_t low_battery; -uint16_t block_time; -uint16_t stage_time; -float climb_sum_err; -float climb_pgain; -float course_pgain; -bool_t in_circle; -int16_t circle_x; -int16_t circle_y; -int16_t circle_radius; +//uint16_t block_time; +//uint16_t stage_time; +//float climb_sum_err; +//float climb_pgain; +//float course_pgain; +//bool_t in_circle; +//int16_t circle_x; +//int16_t circle_y; +//int16_t circle_radius; uint8_t modem_nb_ovrn; uint8_t mcu1_ppm_cpt; diff --git a/sw/airborne/pprz_transport.c b/sw/airborne/pprz_transport.c index be2b820a36..82d544f418 100644 --- a/sw/airborne/pprz_transport.c +++ b/sw/airborne/pprz_transport.c @@ -32,9 +32,3 @@ volatile bool_t pprz_msg_received = FALSE; uint8_t pprz_ovrn, pprz_error; volatile uint8_t payload_length; uint8_t input_payload[MAX_INPUT_PAYLOAD]; - - -#ifdef PPRZ_INPUT -/** FIXME: Where to put it ??? */ -ReceiveUart0(parse_pprz); -#endif diff --git a/sw/airborne/pprz_transport.h b/sw/airborne/pprz_transport.h index 78fb435e34..a206bc073b 100644 --- a/sw/airborne/pprz_transport.h +++ b/sw/airborne/pprz_transport.h @@ -172,5 +172,13 @@ static inline void pprz_parse_payload(void) { dl_msg_available = TRUE; } +#define __PprzLink(dev, _x) dev##_x +#define _PprzLink(dev, _x) __PprzLink(dev, _x) +#define PprzLink(_x) _PprzLink(PPRZ_UART, _x) + +#define PprzBuffer() PprzLink(ChAvailable()) +#define ReadPprzBuffer() { while (PprzLink(ChAvailable())&&!pprz_msg_received) parse_pprz(PprzLink(Getch())); } + + #endif /* PPRZ_TRANSPORT_H */ diff --git a/sw/airborne/radio_control.h b/sw/airborne/radio_control.h index 3cf015d68b..876ae03953 100644 --- a/sw/airborne/radio_control.h +++ b/sw/airborne/radio_control.h @@ -39,7 +39,7 @@ #define RC_AVG_PERIOD 8 #define RC_LOST_TIME 30 /* 500ms with a 60Hz timer */ -#define RC_REALLY_LOST_TIME 100 /* ~1.5s */ +#define RC_REALLY_LOST_TIME 60 /* ~1s */ #define RC_OK 0 #define RC_LOST 1 diff --git a/sw/airborne/wavecard.c b/sw/airborne/wavecard.c index ce28b53cdc..eae046e91d 100644 --- a/sw/airborne/wavecard.c +++ b/sw/airborne/wavecard.c @@ -119,7 +119,7 @@ void wc_parse_payload() { } } -static inline void parse_wc( uint8_t c ) { +void parse_wc( uint8_t c ) { switch (wc_status) { case UNINIT: if (c == WC_SYNC) @@ -172,6 +172,3 @@ static inline void parse_wc( uint8_t c ) { wc_status = UNINIT; return; } - -ReceiveUart0(parse_wc); - diff --git a/sw/airborne/wavecard.h b/sw/airborne/wavecard.h index 3d3f7fc81b..7276f1efde 100644 --- a/sw/airborne/wavecard.h +++ b/sw/airborne/wavecard.h @@ -297,6 +297,15 @@ void wc_debug( void ); WcPut1PayloadByte(channel); \ WcEnd() \ } \ + +void parse_wc( uint8_t c ); + +#define __WavecardLink(dev, _x) dev##_x +#define _WavecardLink(dev, _x) __WavecardLink(dev, _x) +#define WavecardLink(_x) _WavecardLink(WAVECARD_UART, _x) + +#define WavecardBuffer() WavecardLink(ChAvailable()) +#define ReadWavecardBuffer() { while (WavecardLink(ChAvailable())&&!wc_msg_received) parse_wc(WavecardLink(Getch())); } #endif /* WAVECARD_H */ diff --git a/sw/configurator/Makefile b/sw/configurator/Makefile index 060b44d30c..75d4276687 100644 --- a/sw/configurator/Makefile +++ b/sw/configurator/Makefile @@ -31,9 +31,6 @@ all : configurator configurator : $(CMO) $(OCAMLC) -custom -o $@ labltk.cma lib-pprz.cma jpflib.cma $^ - @cat ../../pprz_src_test.sh > $@ - @echo 'ocaml -I +labltk -I $$PAPARAZZI_SRC/sw/lib/ocaml -I $$PAPARAZZI_SRC/sw/configurator labltk.cma ivy-ocaml.cma lib-pprz.cma jpflib.cma $(ABS_CMO) $$*' >> $@ - @chmod a+x $@ %.cmo : %.ml