summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/Makefile3
-rw-r--r--src/drivers/ao_btm.c52
-rw-r--r--src/kernel/ao_serial.h12
-rw-r--r--src/stm/ao_led.c2
-rw-r--r--src/stm/ao_serial_stm.c59
-rw-r--r--src/telebt-v3.0/ao_pins.h202
-rw-r--r--src/telebt-v3.0/ao_telebt.c57
-rw-r--r--src/telebt-v3.0/flash-loader/ao_pins.h34
8 files changed, 410 insertions, 11 deletions
diff --git a/src/Makefile b/src/Makefile
index a5d7b0f3..c8563c9d 100644
--- a/src/Makefile
+++ b/src/Makefile
@@ -36,7 +36,8 @@ ARMM3DIRS=\
telelco-v0.2 telelco-v0.2/flash-loader \
telescience-v0.2 telescience-v0.2/flash-loader \
teledongle-v1.9 teledongle-v1.9/flash-loader \
- teleballoon-v2.0
+ teleballoon-v2.0 \
+ telebt-v3.0 telebt-v3.0/flash-loader
ARMM0DIRS=\
easymini-v1.0 easymini-v1.0/flash-loader
diff --git a/src/drivers/ao_btm.c b/src/drivers/ao_btm.c
index 3b6028a0..9ea638ba 100644
--- a/src/drivers/ao_btm.c
+++ b/src/drivers/ao_btm.c
@@ -16,13 +16,16 @@
*/
#include "ao.h"
+#ifdef AO_BTM_INT_PORT
+#include <ao_exti.h>
+#endif
#ifndef ao_serial_btm_getchar
#define ao_serial_btm_putchar ao_serial1_putchar
#define _ao_serial_btm_pollchar _ao_serial1_pollchar
+#define _ao_serial_btm_sleep() ao_sleep((void *) &ao_serial1_rx_fifo)
#define ao_serial_btm_set_speed ao_serial1_set_speed
#define ao_serial_btm_drain ao_serial1_drain
-#define ao_serial_btm_rx_fifo ao_serial1_rx_fifo
#endif
int8_t ao_btm_stdio;
@@ -125,7 +128,7 @@ ao_btm_getchar(void)
ao_arch_block_interrupts();
while ((c = _ao_serial_btm_pollchar()) == AO_READ_AGAIN) {
ao_alarm(AO_MS_TO_TICKS(10));
- c = ao_sleep(&ao_serial_btm_rx_fifo);
+ c = _ao_serial_btm_sleep();
ao_clear_alarm();
if (c) {
c = AO_READ_AGAIN;
@@ -146,6 +149,7 @@ ao_btm_get_line(void)
{
uint8_t ao_btm_reply_len = 0;
int c;
+ uint8_t l;
while ((c = ao_btm_getchar()) != AO_READ_AGAIN) {
ao_btm_log_in_char(c);
@@ -154,8 +158,8 @@ ao_btm_get_line(void)
if (c == '\r' || c == '\n')
break;
}
- for (c = ao_btm_reply_len; c < sizeof (ao_btm_reply);)
- ao_btm_reply[c++] = '\0';
+ for (l = ao_btm_reply_len; l < sizeof (ao_btm_reply);)
+ ao_btm_reply[l++] = '\0';
return ao_btm_reply_len;
}
@@ -214,7 +218,7 @@ ao_btm_string(__code char *cmd)
{
char c;
- while (c = *cmd++)
+ while ((c = *cmd++) != '\0')
ao_btm_putchar(c);
}
@@ -263,6 +267,12 @@ ao_btm_try_speed(uint8_t speed)
void
ao_btm(void)
{
+#ifdef AO_BTM_RESET_PORT
+ ao_gpio_set(AO_BTM_RESET_PORT, AO_BTM_RESET_PIN, AO_BTM_RESET, 0);
+ ao_delay(AO_MS_TO_TICKS(20));
+ ao_gpio_set(AO_BTM_RESET_PORT, AO_BTM_RESET_PIN, AO_BTM_RESET, 1);
+#endif
+
/*
* Wait for the bluetooth device to boot
*/
@@ -316,6 +326,7 @@ __xdata struct ao_task ao_btm_task;
#define BT_PDIR P2DIR
#define BT_PINP P2INP
#define BT_IEN2_PIE IEN2_P2IE
+#define BT_CC1111 1
#endif
#if BT_LINK_ON_P1
#define BT_PICTL_ICON PICTL_P1ICON
@@ -323,11 +334,13 @@ __xdata struct ao_task ao_btm_task;
#define BT_PDIR P1DIR
#define BT_PINP P1INP
#define BT_IEN2_PIE IEN2_P1IE
+#define BT_CC1111 1
#endif
void
ao_btm_check_link()
{
+#if BT_CC1111
ao_arch_critical(
/* Check the pin and configure the interrupt detector to wait for the
* pin to flip the other way
@@ -340,8 +353,10 @@ ao_btm_check_link()
PICTL &= ~BT_PICTL_ICON;
}
);
+#endif
}
+#if BT_CC1111
void
ao_btm_isr(void)
#if BT_LINK_ON_P1
@@ -357,6 +372,16 @@ ao_btm_isr(void)
}
BT_PIFG = 0;
}
+#endif
+
+#ifdef AO_BTM_INT_PORT
+void
+ao_btm_isr(void)
+{
+ ao_btm_check_link();
+ ao_wakeup(&ao_btm_connected);
+}
+#endif
void
ao_btm_init (void)
@@ -365,6 +390,18 @@ ao_btm_init (void)
ao_serial_btm_set_speed(AO_SERIAL_SPEED_19200);
+#ifdef AO_BTM_RESET_PORT
+ ao_enable_output(AO_BTM_RESET_PORT,AO_BTM_RESET_PIN,AO_BTM_RESET,0);
+#endif
+
+#ifdef AO_BTM_INT_PORT
+ ao_enable_port(AO_BTM_INT_PORT);
+ ao_exti_setup(AO_BTM_INT_PORT, AO_BTM_INT_PIN,
+ AO_EXTI_MODE_FALLING|AO_EXTI_MODE_RISING|AO_EXTI_PRIORITY_LOW,
+ ao_btm_isr);
+#endif
+
+#if BT_CC1111
#if BT_LINK_ON_P1
/*
* Configure ser reset line
@@ -386,10 +423,15 @@ ao_btm_init (void)
/* Enable interrupts */
IEN2 |= BT_IEN2_PIE;
+#endif
/* Check current pin state */
ao_btm_check_link();
+#ifdef AO_BTM_INT_PORT
+ ao_exti_enable(AO_BTM_INT_PORT, AO_BTM_INT_PIN);
+#endif
+
#if BT_LINK_ON_P2
/* Eable the pin interrupt */
PICTL |= PICTL_P2IEN;
diff --git a/src/kernel/ao_serial.h b/src/kernel/ao_serial.h
index baf213c0..dbc9f8e4 100644
--- a/src/kernel/ao_serial.h
+++ b/src/kernel/ao_serial.h
@@ -34,6 +34,9 @@ ao_serial0_getchar(void);
int
_ao_serial0_pollchar(void);
+uint8_t
+_ao_serial0_sleep(void);
+
void
ao_serial0_putchar(char c);
@@ -54,6 +57,9 @@ ao_serial1_getchar(void);
int
_ao_serial1_pollchar(void);
+uint8_t
+_ao_serial1_sleep(void);
+
void
ao_serial1_putchar(char c);
@@ -74,6 +80,9 @@ ao_serial2_getchar(void);
int
_ao_serial2_pollchar(void);
+uint8_t
+_ao_serial2_sleep(void);
+
void
ao_serial2_putchar(char c);
@@ -94,6 +103,9 @@ ao_serial3_getchar(void);
int
_ao_serial3_pollchar(void);
+uint8_t
+_ao_serial3_sleep(void);
+
void
ao_serial3_putchar(char c);
diff --git a/src/stm/ao_led.c b/src/stm/ao_led.c
index 0acab106..9b61cf62 100644
--- a/src/stm/ao_led.c
+++ b/src/stm/ao_led.c
@@ -86,7 +86,7 @@ ao_led_for(uint16_t colors, uint16_t ticks) __reentrant
stm_moder_set(port, bit, STM_MODER_OUTPUT); \
stm_otyper_set(port, bit, STM_OTYPER_PUSH_PULL); \
} while (0)
-
+
void
ao_led_init(uint16_t enable)
{
diff --git a/src/stm/ao_serial_stm.c b/src/stm/ao_serial_stm.c
index 2133c584..e356b944 100644
--- a/src/stm/ao_serial_stm.c
+++ b/src/stm/ao_serial_stm.c
@@ -63,7 +63,7 @@ int
_ao_usart_pollchar(struct ao_stm_usart *usart)
{
int c;
-
+
if (ao_fifo_empty(usart->rx_fifo))
c = AO_READ_AGAIN;
else {
@@ -85,6 +85,12 @@ ao_usart_getchar(struct ao_stm_usart *usart)
return (char) c;
}
+static inline uint8_t
+_ao_usart_sleep(struct ao_stm_usart *usart)
+{
+ return ao_sleep(&usart->rx_fifo);
+}
+
void
ao_usart_putchar(struct ao_stm_usart *usart, char c)
{
@@ -179,6 +185,13 @@ ao_usart_init(struct ao_stm_usart *usart)
ao_usart_set_speed(usart, AO_SERIAL_SPEED_9600);
}
+void
+ao_usart_set_flow(struct ao_stm_usart *usart)
+{
+ usart->reg->cr3 |= ((1 << STM_USART_CR3_CTSE) |
+ (1 << STM_USART_CR3_RTSE));
+}
+
#if HAS_SERIAL_1
struct ao_stm_usart ao_stm_usart1;
@@ -203,6 +216,18 @@ _ao_serial1_pollchar(void)
return _ao_usart_pollchar(&ao_stm_usart1);
}
+uint8_t
+_ao_serial1_sleep(void)
+{
+ return _ao_usart_sleep(&ao_stm_usart1);
+}
+
+void
+ao_serial1_drain(void)
+{
+ ao_usart_drain(&ao_stm_usart1);
+}
+
void
ao_serial1_set_speed(uint8_t speed)
{
@@ -234,6 +259,18 @@ _ao_serial2_pollchar(void)
return _ao_usart_pollchar(&ao_stm_usart2);
}
+uint8_t
+_ao_serial2_sleep(void)
+{
+ return _ao_usart_sleep(&ao_stm_usart2);
+}
+
+void
+ao_serial2_drain(void)
+{
+ ao_usart_drain(&ao_stm_usart2);
+}
+
void
ao_serial2_set_speed(uint8_t speed)
{
@@ -265,6 +302,12 @@ _ao_serial3_pollchar(void)
return _ao_usart_pollchar(&ao_stm_usart3);
}
+uint8_t
+_ao_serial3_sleep(void)
+{
+ return _ao_usart_sleep(&ao_stm_usart3);
+}
+
void
ao_serial3_set_speed(uint8_t speed)
{
@@ -324,21 +367,31 @@ ao_serial_init(void)
stm_afr_set(&stm_gpioa, 2, STM_AFR_AF7);
stm_afr_set(&stm_gpioa, 3, STM_AFR_AF7);
+#if USE_SERIAL_2_FLOW
+ stm_afr_set(&stm_gpioa, 0, STM_AFR_AF7);
+ stm_afr_set(&stm_gpioa, 1, STM_AFR_AF7);
+#endif
#else
#if SERIAL_2_PD5_PD6
stm_rcc.ahbenr |= (1 << STM_RCC_AHBENR_GPIODEN);
stm_afr_set(&stm_gpiod, 5, STM_AFR_AF7);
stm_afr_set(&stm_gpiod, 6, STM_AFR_AF7);
+#if USE_SERIAL_2_FLOW
+#error "Don't know how to set flowcontrol for serial 2 on PD"
+#endif
#else
#error "No SERIAL_2 port configuration specified"
-#endif
+#endif
#endif
/* Enable USART */
stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_USART2EN);
ao_stm_usart2.reg = &stm_usart2;
ao_usart_init(&ao_stm_usart2);
+#if USE_SERIAL_2_FLOW
+ ao_usart_set_flow(&ao_stm_usart2);
+#endif
stm_nvic_set_enable(STM_ISR_USART2_POS);
stm_nvic_set_priority(STM_ISR_USART2_POS, 4);
@@ -393,5 +446,3 @@ ao_serial_init(void)
#endif
#endif
}
-
-
diff --git a/src/telebt-v3.0/ao_pins.h b/src/telebt-v3.0/ao_pins.h
new file mode 100644
index 00000000..0d03f94d
--- /dev/null
+++ b/src/telebt-v3.0/ao_pins.h
@@ -0,0 +1,202 @@
+/*
+ * Copyright © 2012 Keith Packard <keithp@keithp.com>
+ *
+ * This program 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; version 2 of the License.
+ *
+ * This program 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 this program; if not, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+ */
+
+#ifndef _AO_PINS_H_
+#define _AO_PINS_H_
+
+#define HAS_TASK_QUEUE 1
+
+/* 8MHz High speed external crystal */
+#define AO_HSE 8000000
+
+/* PLLVCO = 96MHz (so that USB will work) */
+#define AO_PLLMUL 12
+#define AO_RCC_CFGR_PLLMUL (STM_RCC_CFGR_PLLMUL_12)
+
+/* SYSCLK = 32MHz (no need to go faster than CPU) */
+#define AO_PLLDIV 3
+#define AO_RCC_CFGR_PLLDIV (STM_RCC_CFGR_PLLDIV_3)
+
+/* HCLK = 32MHz (CPU clock) */
+#define AO_AHB_PRESCALER 1
+#define AO_RCC_CFGR_HPRE_DIV STM_RCC_CFGR_HPRE_DIV_1
+
+/* Run APB1 at 16MHz (HCLK/2) */
+#define AO_APB1_PRESCALER 2
+#define AO_RCC_CFGR_PPRE1_DIV STM_RCC_CFGR_PPRE2_DIV_2
+
+/* Run APB2 at 16MHz (HCLK/2) */
+#define AO_APB2_PRESCALER 2
+#define AO_RCC_CFGR_PPRE2_DIV STM_RCC_CFGR_PPRE2_DIV_2
+
+#define HAS_SERIAL_1 0
+#define USE_SERIAL_1_STDIN 0
+#define SERIAL_1_PB6_PB7 0
+#define SERIAL_1_PA9_PA10 1
+
+#define HAS_SERIAL_2 1
+#define USE_SERIAL_2_STDIN 0
+#define USE_SERIAL_2_FLOW 1
+#define SERIAL_2_PA2_PA3 1
+#define SERIAL_2_PD5_PD6 0
+
+#define HAS_SERIAL_3 1
+#define USE_SERIAL_3_STDIN 0
+#define SERIAL_3_PB10_PB11 1
+#define SERIAL_3_PC10_PC11 0
+#define SERIAL_3_PD8_PD9 0
+
+#define AO_CONFIG_MAX_SIZE 1024
+
+#define HAS_EEPROM 1
+#define USE_INTERNAL_FLASH 0
+#define USE_EEPROM_CONFIG 1
+#define USE_STORAGE_CONFIG 0
+#define HAS_USB 1
+#define HAS_BEEP 0
+#define HAS_BATTERY_REPORT 0
+#define HAS_RADIO 1
+#define HAS_TELEMETRY 0
+#define HAS_APRS 0
+#define HAS_ACCEL 0
+
+#define HAS_SPI_1 1
+#define SPI_1_PA5_PA6_PA7 1 /* CC1200 */
+#define SPI_1_PB3_PB4_PB5 0
+#define SPI_1_PE13_PE14_PE15 0
+#define SPI_1_OSPEEDR STM_OSPEEDR_10MHz
+
+#define HAS_SPI_2 0
+#define SPI_2_PB13_PB14_PB15 0
+#define SPI_2_PD1_PD3_PD4 0
+#define SPI_2_OSPEEDR STM_OSPEEDR_10MHz
+
+#define HAS_I2C_1 0
+#define I2C_1_PB8_PB9 0
+
+#define HAS_I2C_2 0
+#define I2C_2_PB10_PB11 0
+
+#define PACKET_HAS_SLAVE 0
+#define PACKET_HAS_MASTER 1
+
+#define LOW_LEVEL_DEBUG 0
+
+#define LED_PORT_0_ENABLE STM_RCC_AHBENR_GPIOAEN
+#define LED_PORT_1_ENABLE STM_RCC_AHBENR_GPIOCEN
+#define LED_PORT_0 (&stm_gpioa)
+#define LED_PORT_1 (&stm_gpioc)
+#define LED_PORT_0_SHIFT 0
+#define LED_PORT_1_SHIFT 0
+#define LED_PIN_RED (4 + LED_PORT_0_SHIFT)
+#define LED_PIN_BLUE (15 + LED_PORT_1_SHIFT)
+#define AO_LED_RED (1 << LED_PIN_RED)
+#define AO_LED_BLUE (1 << LED_PIN_BLUE)
+#define LED_PORT_0_MASK (AO_LED_RED)
+#define LED_PORT_1_MASK (AO_LED_BLUE)
+#define AO_BT_LED AO_LED_BLUE
+
+#define LEDS_AVAILABLE (AO_LED_RED | AO_LED_BLUE)
+
+#define HAS_GPS 0
+#define HAS_FLIGHT 0
+#define HAS_ADC 1
+#define HAS_ADC_TEMP 0
+#define HAS_LOG 0
+
+/*
+ * ADC
+ */
+#define AO_DATA_RING 32
+#define AO_ADC_NUM_SENSE 2
+
+struct ao_adc {
+ int16_t v_batt;
+};
+
+#define AO_ADC_DUMP(p) \
+ printf("tick: %5u %5d batt: %5d\n", \
+ (p)->tick, \
+ (p)->adc.v_batt);
+
+#define AO_ADC_V_BATT 8
+#define AO_ADC_V_BATT_PORT (&stm_gpiob)
+#define AO_ADC_V_BATT_PIN 0
+
+#define AO_ADC_RCC_AHBENR ((1 << STM_RCC_AHBENR_GPIOEEN))
+
+#define AO_NUM_ADC_PIN 1
+
+#define AO_ADC_PIN0_PORT AO_ADC_V_BATT_PORT
+#define AO_ADC_PIN0_PIN AO_ADC_V_BATT_PIN
+
+#define AO_NUM_ADC (AO_NUM_ADC_PIN)
+
+#define AO_ADC_SQ1 AO_ADC_V_BATT
+
+/*
+ * Voltage divider on ADC battery sampler
+ */
+#define AO_BATTERY_DIV_PLUS 51 /* 5.6k */
+#define AO_BATTERY_DIV_MINUS 100 /* 10k */
+
+/*
+ * ADC reference in decivolts
+ */
+#define AO_ADC_REFERENCE_DV 33
+
+/*
+ * BTM
+ */
+#define HAS_BTM 1
+
+#define ao_serial_btm_getchar ao_serial2_getchar
+#define ao_serial_btm_putchar ao_serial2_putchar
+#define _ao_serial_btm_pollchar _ao_serial2_pollchar
+#define _ao_serial_btm_sleep _ao_serial2_sleep
+#define ao_serial_btm_set_speed ao_serial2_set_speed
+#define ao_serial_btm_drain ao_serial2_drain
+#define ao_serial_btm_rx_fifo ao_serial2_rx_fifo
+
+#define AO_BTM_INT_PORT (&stm_gpioa)
+#define AO_BTM_INT_PIN 15
+#define AO_BTM_RESET_PORT (&stm_gpiob)
+#define AO_BTM_RESET_PIN 3
+
+/*
+ * Radio (cc1200)
+ */
+
+/* gets pretty close to 434.550 */
+
+#define AO_RADIO_CAL_DEFAULT 0x6ca333
+
+#define AO_FEC_DEBUG 0
+#define AO_CC1200_SPI_CS_PORT (&stm_gpiob)
+#define AO_CC1200_SPI_CS_PIN 10
+#define AO_CC1200_SPI_BUS AO_SPI_1_PA5_PA6_PA7
+#define AO_CC1200_SPI stm_spi1
+
+#define AO_CC1200_INT_PORT (&stm_gpiob)
+#define AO_CC1200_INT_PIN (11)
+
+#define AO_CC1200_INT_GPIO 2
+#define AO_CC1200_INT_GPIO_IOCFG CC1200_IOCFG2
+
+#define HAS_BOOT_RADIO 0
+
+#endif /* _AO_PINS_H_ */
diff --git a/src/telebt-v3.0/ao_telebt.c b/src/telebt-v3.0/ao_telebt.c
new file mode 100644
index 00000000..f3906e3f
--- /dev/null
+++ b/src/telebt-v3.0/ao_telebt.c
@@ -0,0 +1,57 @@
+/*
+ * Copyright © 2015 Keith Packard <keithp@keithp.com>
+ *
+ * This program 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; version 2 of the License.
+ *
+ * This program 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 this program; if not, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+ */
+
+#include <ao.h>
+#include <ao_exti.h>
+#include <ao_packet.h>
+#include <ao_eeprom.h>
+#include <ao_profile.h>
+#include <ao_btm.h>
+#if HAS_SAMPLE_PROFILE
+#include <ao_sample_profile.h>
+#endif
+
+int
+main(void)
+{
+ ao_clock_init();
+
+ ao_task_init();
+ ao_serial_init();
+ ao_led_init(LEDS_AVAILABLE);
+ ao_led_on(AO_LED_RED);
+ ao_timer_init();
+
+ ao_spi_init();
+ ao_dma_init();
+ ao_exti_init();
+
+ ao_adc_init();
+ ao_btm_init();
+ ao_cmd_init();
+
+ ao_eeprom_init();
+
+ ao_usb_init();
+ ao_radio_init();
+ ao_packet_master_init();
+
+ ao_config_init();
+
+ ao_start_scheduler();
+ return 0;
+}
diff --git a/src/telebt-v3.0/flash-loader/ao_pins.h b/src/telebt-v3.0/flash-loader/ao_pins.h
new file mode 100644
index 00000000..8711548d
--- /dev/null
+++ b/src/telebt-v3.0/flash-loader/ao_pins.h
@@ -0,0 +1,34 @@
+/*
+ * Copyright © 2013 Keith Packard <keithp@keithp.com>
+ *
+ * This program 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; version 2 of the License.
+ *
+ * This program 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 this program; if not, write to the Free Software Foundation, Inc.,
+ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA.
+ */
+
+#ifndef _AO_PINS_H_
+#define _AO_PINS_H_
+
+/* External crystal at 8MHz */
+#define AO_HSE 8000000
+
+#include <ao_flash_stm_pins.h>
+
+/* Blue LED */
+
+#define AO_BOOT_PIN 1
+#define AO_BOOT_APPLICATION_GPIO stm_gpioc
+#define AO_BOOT_APPLICATION_PIN 15
+#define AO_BOOT_APPLICATION_VALUE 0
+#define AO_BOOT_APPLICATION_MODE AO_EXTI_MODE_PULL_DOWN
+
+#endif /* _AO_PINS_H_ */