diff options
| -rw-r--r-- | src/micropeak-v2.0/.gitignore | 3 | ||||
| -rw-r--r-- | src/micropeak-v2.0/Makefile | 100 | ||||
| -rw-r--r-- | src/micropeak-v2.0/ao_micropeak.c | 278 | ||||
| -rw-r--r-- | src/micropeak-v2.0/ao_pins.h | 144 | ||||
| -rw-r--r-- | src/micropeak-v2.0/flash-loader/.gitignore | 2 | ||||
| -rw-r--r-- | src/micropeak-v2.0/flash-loader/Makefile | 8 | ||||
| -rw-r--r-- | src/micropeak-v2.0/flash-loader/ao_pins.h | 37 | ||||
| -rw-r--r-- | src/micropeak-v2.0/micropeak.ld | 123 | 
8 files changed, 695 insertions, 0 deletions
| diff --git a/src/micropeak-v2.0/.gitignore b/src/micropeak-v2.0/.gitignore new file mode 100644 index 00000000..c2062c34 --- /dev/null +++ b/src/micropeak-v2.0/.gitignore @@ -0,0 +1,3 @@ +ao_product.h +microsplash-v* +microsplash-load diff --git a/src/micropeak-v2.0/Makefile b/src/micropeak-v2.0/Makefile new file mode 100644 index 00000000..32154fa6 --- /dev/null +++ b/src/micropeak-v2.0/Makefile @@ -0,0 +1,100 @@ +# +# Tiny AltOS build +# +# + +include ../stmf0/Makefile.defs + +PUBLISH_DIR=$(HOME)/altusmetrumllc/Binaries +PUBLISH_HEX=$(PUBLISH_DIR)/$(HEX) + +MICRO_SRC=\ +	ao_report_micro.c \ +	ao_log_micro.c \ +	ao_microflight.c \ +	ao_microkalman.c + +ALTOS_SRC = \ +	ao_micropeak.c \ +	ao_spi_stm.c \ +	ao_dma_stm.c \ +	ao_led.c \ +	ao_timer.c \ +	ao_ms5607.c \ +	ao_exti_stm.c \ +	ao_convert_pa.c \ +	ao_romconfig.c \ +	ao_product.c \ +	ao_panic.c \ +	ao_stdio.c \ +	ao_serial_stm.c \ +	ao_usb_stm.c \ +	ao_mutex.c \ +	ao_interrupt.c \ +	ao_cmd.c \ +	ao_task.c \ +	ao_data.c \ +	ao_boot_chain.c \ +	ao_microflight.c \ +	ao_report_micro.c \ +	ao_storage_stm.c \ +	ao_storage.c \ +	ao_log_micro.c \ +	ao_microkalman.c + +INC=\ +	ao.h \ +	ao_pins.h \ +	ao_arch.h \ +	ao_arch_funcs.h \ +	ao_exti.h \ +	ao_ms5607.h \ +	ao_log_micro.h \ +	ao_micropeak.h \ +	altitude-pa.h \ +	stm32f0.h + +IDPRODUCT=0x14 +PRODUCT=MicroPeak-v2.0 +PRODUCT_DEF=-DMICROPEAK + +CFLAGS = $(PRODUCT_DEF) $(STMF0_CFLAGS) -g -Os + +PROGNAME=micropeak-v2.0 +PROG=$(PROGNAME)-$(VERSION).elf +HEX=$(PROGNAME)-$(VERSION).ihx + +SRC=$(ALTOS_SRC) +OBJ=$(SRC:.c=.o) + +all: $(PROG) $(HEX) + +LDFLAGS=$(CFLAGS) -L$(TOPDIR)/stmf0 -Wl,-Tmicropeak.ld -n + +$(PROG): Makefile $(OBJ) micropeak.ld +	$(call quiet,CC) $(LDFLAGS) $(CFLAGS) -o $(PROG) $(OBJ) $(LIBS) + +ao_product.h: ao-make-product.5c ../Version +	$(call quiet,NICKLE,$<) $< -m altusmetrum.org -i $(IDPRODUCT) -p $(PRODUCT) -v $(VERSION) > $@ + +ao_product.o: ao_product.c ao_product.h + +distclean:	clean + +clean: +	rm -f *.o *.elf *.ihx +	rm -f ao_product.h + +publish: $(PUBLISH_HEX) + +$(PUBLISH_HEX): $(HEX) +	cp -a $(HEX) $@ + +../altitude-pa.h: make-altitude-pa +	nickle $< > $@ + +install: + +uninstall: + +$(OBJ): ao_product.h $(INC) diff --git a/src/micropeak-v2.0/ao_micropeak.c b/src/micropeak-v2.0/ao_micropeak.c new file mode 100644 index 00000000..1cfa1209 --- /dev/null +++ b/src/micropeak-v2.0/ao_micropeak.c @@ -0,0 +1,278 @@ +/* + * Copyright © 2017 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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_micropeak.h> +#include <ao_report_micro.h> +#include <ao_log_micro.h> +#include <ao_storage.h> + +static struct ao_ms5607_value	value; + +alt_t		ground_alt, max_alt; +alt_t		ao_max_height; + +void +ao_pa_get(void) +{ +	ao_ms5607_sample(&ao_ms5607_current); +	ao_ms5607_convert(&ao_ms5607_current, &value); +	pa = value.pres; +} + +static void +ao_compute_height(void) +{ +	ground_alt = ao_pa_to_altitude(pa_ground); +	max_alt = ao_pa_to_altitude(pa_min); +	ao_max_height = max_alt - ground_alt; +} + +static void +ao_pips(void) +{ +	uint8_t	i; +	for (i = 0; i < 10; i++) { +		ao_led_toggle(AO_LED_REPORT); +		ao_delay(AO_MS_TO_TICKS(80)); +	} +	ao_delay(AO_MS_TO_TICKS(200)); +} + +void +ao_delay_until(uint16_t target) { +	int16_t	delay = target - ao_time(); +	if (delay > 0) { +		ao_sleep_for(ao_delay_until, delay); +	} +} + +static struct ao_task mp_task; + +static void +ao_battery_disable(void) +{ +	/* Disable */ +	if (stm_adc.cr & (1 << STM_ADC_CR_ADEN)) { +		stm_adc.cr |= (1 << STM_ADC_CR_ADDIS); +		while (stm_adc.cr & (1 << STM_ADC_CR_ADDIS)) +			; +	} + +	/* Turn off everything */ +	stm_adc.cr &= ~((1 << STM_ADC_CR_ADCAL) | +			(1 << STM_ADC_CR_ADSTP) | +			(1 << STM_ADC_CR_ADSTART) | +			(1 << STM_ADC_CR_ADEN)); +} + +static void +ao_battery_init(void) +{ +	stm_rcc.apb2enr |= (1 << STM_RCC_APB2ENR_ADCEN); + +	ao_battery_disable(); + +	/* Configure */ +	stm_adc.cfgr1 = ((0 << STM_ADC_CFGR1_AWDCH) |				  /* analog watchdog channel 0 */ +			 (0 << STM_ADC_CFGR1_AWDEN) |				  /* Disable analog watchdog */ +			 (0 << STM_ADC_CFGR1_AWDSGL) |				  /* analog watchdog on all channels */ +			 (0 << STM_ADC_CFGR1_DISCEN) |				  /* Not discontinuous mode. All channels converted with one trigger */ +			 (0 << STM_ADC_CFGR1_AUTOOFF) |				  /* Leave ADC running */ +			 (1 << STM_ADC_CFGR1_WAIT) |				  /* Wait for data to be read before next conversion */ +			 (0 << STM_ADC_CFGR1_CONT) |				  /* only one set of conversions per trigger */ +			 (1 << STM_ADC_CFGR1_OVRMOD) |				  /* overwrite on overrun */ +			 (STM_ADC_CFGR1_EXTEN_DISABLE << STM_ADC_CFGR1_EXTEN) |	  /* SW trigger */ +			 (0 << STM_ADC_CFGR1_ALIGN) |				  /* Align to LSB */ +			 (STM_ADC_CFGR1_RES_12 << STM_ADC_CFGR1_RES) |		  /* 12 bit resolution */ +			 (STM_ADC_CFGR1_SCANDIR_UP << STM_ADC_CFGR1_SCANDIR) |	  /* scan 0 .. n */ +			 (STM_ADC_CFGR1_DMACFG_ONESHOT << STM_ADC_CFGR1_DMACFG) | /* one set of conversions then stop */ +			 (1 << STM_ADC_CFGR1_DMAEN));				  /* enable DMA */ + +	/* Set the clock */ +	stm_adc.cfgr2 = STM_ADC_CFGR2_CKMODE_PCLK_2 << STM_ADC_CFGR2_CKMODE; + +	/* Shortest sample time */ +	stm_adc.smpr = STM_ADC_SMPR_SMP_71_5 << STM_ADC_SMPR_SMP; + +	/* Select Vref */ +	stm_adc.chselr = 1 << 17; + +	stm_adc.ccr = ((0 << STM_ADC_CCR_VBATEN) | +		       (0 << STM_ADC_CCR_TSEN) | +		       (1 << STM_ADC_CCR_VREFEN)); + +	/* Calibrate */ +	stm_adc.cr |= (1 << STM_ADC_CR_ADCAL); +	while ((stm_adc.cr & (1 << STM_ADC_CR_ADCAL)) != 0) +		; + +	/* Enable */ +	stm_adc.cr |= (1 << STM_ADC_CR_ADEN); +	while ((stm_adc.isr & (1 << STM_ADC_ISR_ADRDY)) == 0) +		; + +	/* Clear any stale status bits */ +	stm_adc.isr = 0; + +	/* Turn on syscfg */ +	stm_rcc.apb2enr |= (1 << STM_RCC_APB2ENR_SYSCFGCOMPEN); +} + +static void +ao_battery_fini(void) +{ +	/* Disable */ +	ao_battery_disable(); + +	/* Power down */ +	stm_rcc.apb2enr &= ~(1 << STM_RCC_APB2ENR_ADCEN); +} + +static uint16_t +ao_battery_voltage(void) +{ +	uint16_t	vrefint; + +	ao_battery_init(); + +	stm_adc.cr |= (1 << STM_ADC_CR_ADSTART); + +	while ((stm_adc.isr & (1 << STM_ADC_ISR_EOC)) == 0) +		ao_arch_nop(); + +	vrefint = stm_adc.dr; + +	ao_battery_fini(); + +	return 330 * stm_cal.vrefint_cal / vrefint; +} + + +uint8_t	ao_on_battery; + +static void +ao_micropeak(void) +{ +	ao_ms5607_setup(); +	ao_storage_setup(); + +	/* Give the person a second to get their finger out of the way */ +	ao_delay(AO_MS_TO_TICKS(1000)); + +	ao_pips(); + +	ao_log_micro_restore(); +	ao_compute_height(); +	ao_report_altitude(); +	ao_log_micro_dump(); + +#if BOOST_DELAY +	ao_delay(BOOST_DELAY); +#endif + +	ao_microflight(); + +	ao_log_micro_save(); +	ao_compute_height(); +	ao_report_altitude(); + +	ao_sleep(&ao_on_battery); +} + +static void +ao_show_bat(void) +{ +	printf("battery: %u\n", ao_battery_voltage()); +} + +static struct ao_cmds mp_cmd[] = { +	{ ao_show_bat, "b\0Show battery voltage" }, +	{ 0 } +}; + +static void +ao_hsi_init(void) +{ +	uint32_t	cfgr; + +	/* Disable all interrupts */ +	stm_rcc.cir = 0; + +	/* Enable prefetch */ +	stm_flash.acr |= (1 << STM_FLASH_ACR_PRFTBE); + +	/* Enable power interface clock */ +	stm_rcc.apb1enr |= (1 << STM_RCC_APB1ENR_PWREN); + +	/* HCLK to 48MHz -> AHB prescaler = /1 */ +	cfgr = stm_rcc.cfgr; +	cfgr &= ~(STM_RCC_CFGR_HPRE_MASK << STM_RCC_CFGR_HPRE); +	cfgr |= (AO_RCC_CFGR_HPRE_DIV << STM_RCC_CFGR_HPRE); +	stm_rcc.cfgr = cfgr; +	while ((stm_rcc.cfgr & (STM_RCC_CFGR_HPRE_MASK << STM_RCC_CFGR_HPRE)) != +	       (AO_RCC_CFGR_HPRE_DIV << STM_RCC_CFGR_HPRE)) +		ao_arch_nop(); + +	/* APB Prescaler = AO_APB_PRESCALER */ +	cfgr = stm_rcc.cfgr; +	cfgr &= ~(STM_RCC_CFGR_PPRE_MASK << STM_RCC_CFGR_PPRE); +	cfgr |= (AO_RCC_CFGR_PPRE_DIV << STM_RCC_CFGR_PPRE); +	stm_rcc.cfgr = cfgr; + +	/* Clear reset flags */ +	stm_rcc.csr |= (1 << STM_RCC_CSR_RMVF); +} + +void +main(void) +{ +	if (ao_battery_voltage() < 320) +		ao_on_battery = 1; + +	/* Leave the system running on the HSI if we're on battery */ +	if (!ao_on_battery) +		ao_clock_init(); +	else +		ao_hsi_init(); + +	ao_led_init(LEDS_AVAILABLE); +	ao_task_init(); +	ao_timer_init(); +	ao_serial_init(); +	stm_moder_set(&stm_gpioa, 2, STM_MODER_OUTPUT); + +	ao_dma_init(); +	ao_spi_init(); +	ao_exti_init(); + +	/* Leave USB disabled on battery */ +	if (!ao_on_battery) { +		ao_usb_init(); +		ao_cmd_init(); +	} + +	ao_ms5607_init(); + +	ao_storage_init(); + +	ao_add_task(&mp_task, ao_micropeak, "micropeak"); +	ao_cmd_register(mp_cmd); +	ao_start_scheduler(); +} diff --git a/src/micropeak-v2.0/ao_pins.h b/src/micropeak-v2.0/ao_pins.h new file mode 100644 index 00000000..13a4fd10 --- /dev/null +++ b/src/micropeak-v2.0/ao_pins.h @@ -0,0 +1,144 @@ +/* + * Copyright © 2011 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_ + +extern uint8_t ao_on_battery; + +#define AO_SYSCLK	(ao_on_battery ? STM_HSI_FREQ : 48000000) + +#define LED_PORT_ENABLE	STM_RCC_AHBENR_IOPAEN +#define LED_PORT	(&stm_gpioa) +#define LED_PIN_ORANGE	2 +#define AO_LED_ORANGE	(1 << LED_PIN_ORANGE) +#define AO_LED_REPORT	AO_LED_ORANGE +#define AO_LED_PANIC	AO_LED_ORANGE + +#define LEDS_AVAILABLE	(AO_LED_ORANGE) + +#define AO_POWER_MANAGEMENT	0 + +/* 48MHz clock based on USB */ +#define AO_HSI48	1 +/* Need HSI running to flash */ +#define AO_NEED_HSI	1 + +/* HCLK = 12MHz usb / 2MHz battery */ +#define AO_AHB_PRESCALER	(ao_on_battery ? 16 : 1) +#define AO_RCC_CFGR_HPRE_DIV	(ao_on_battery ? STM_RCC_CFGR_HPRE_DIV_16 : STM_RCC_CFGR_HPRE_DIV_1) + +/* APB = 12MHz usb / 2MHz battery */ +#define AO_APB_PRESCALER	1 +#define AO_RCC_CFGR_PPRE_DIV	STM_RCC_CFGR_PPRE_DIV_1 + +#define HAS_USB			1 +#define AO_PA11_PA12_RMP	1 + +#define PACKET_HAS_SLAVE	0 +#define HAS_SERIAL_1		0 +#define HAS_SERIAL_2		1 +#define USE_SERIAL_2_STDIN	0 +#define HAS_SERIAL_SW_FLOW	0 +#define SERIAL_2_PA2_PA3	1 +#define SERIAL_2_PA14_PA15	0 +#define USE_SERIAL2_FLOW	0 +#define USE_SERIAL2_SW_FLOW	0 + +#define IS_FLASH_LOADER		0 + +#define HAS_MS5607		1 +#define HAS_MS5611		0 +#define HAS_MS5607_TASK		0 +#define HAS_EEPROM		0 +#define HAS_BEEP		0 + +/* Logging */ +#define LOG_INTERVAL		1 +#define SAMPLE_SLEEP		AO_MS_TO_TICKS(100) +#define BOOST_DELAY		AO_SEC_TO_TICKS(60) +#define AO_LOG_ID		AO_LOG_ID_MICRO_PEAK2 + +/* Kalman filter */ + +#define AO_MK_STEP_100MS	1 +#define AO_MK_STEP_96MS		0 + +/* SPI */ +#define HAS_SPI_1		1 +#define SPI_1_PA5_PA6_PA7	1 +#define SPI_1_PB3_PB4_PB5	0 +#define SPI_1_OSPEEDR		STM_OSPEEDR_MEDIUM + +#define HAS_SPI_2		0 + +/* MS5607 */ +#define HAS_MS5607		1 +#define HAS_MS5611		0 +#define AO_MS5607_PRIVATE_PINS	0 +#define AO_MS5607_CS_PORT	(&stm_gpioa) +#define AO_MS5607_CS_PIN	4 +#define AO_MS5607_CS_MASK	(1 << AO_MS5607_CS_PIN) +#define AO_MS5607_MISO_PORT	(&stm_gpioa) +#define AO_MS5607_MISO_PIN	6 +#define AO_MS5607_MISO_MASK	(1 << AO_MS5607_MISO_PIN) +#define AO_MS5607_SPI_INDEX	AO_SPI_1_PA5_PA6_PA7 + +typedef int32_t alt_t; + +#define AO_ALT_VALUE(x)		((x) * (alt_t) 10) + +#define AO_DATA_RING		32 + +#define HAS_ADC			0 + +static inline void +ao_power_off(void) __attribute((noreturn)); + +static inline void +ao_power_off(void) { +	for (;;) { +	} +} + +extern alt_t ao_max_height; + +void ao_delay_until(uint16_t target); + +#define ao_async_stop() do {					\ +		ao_serial2_drain();				\ +		stm_moder_set(&stm_gpioa, 2, STM_MODER_OUTPUT); \ +	} while (0) + +#define ao_async_start() do {						\ +		stm_moder_set(&stm_gpioa, 2, STM_MODER_ALTERNATE);	\ +		ao_delay(AO_MS_TO_TICKS(100));				\ +	} while (0) + +#define ao_async_byte(b) ao_serial2_putchar((char) (b)) + +#define ao_eeprom_read(pos, ptr, size) ao_storage_read(pos, ptr, size) +#define ao_eeprom_write(pos, ptr, size) ao_storage_write(pos, ptr, size) +#define MAX_LOG_OFFSET	ao_storage_total + +extern uint32_t __flash__[]; +extern uint32_t __flash_end__[]; + +#define AO_BOOT_APPLICATION_BOUND	((uint32_t *) __flash__) +#define USE_STORAGE_CONFIG	0 + +#endif /* _AO_PINS_H_ */ diff --git a/src/micropeak-v2.0/flash-loader/.gitignore b/src/micropeak-v2.0/flash-loader/.gitignore new file mode 100644 index 00000000..43f0aa8d --- /dev/null +++ b/src/micropeak-v2.0/flash-loader/.gitignore @@ -0,0 +1,2 @@ +*.bin +*.elf diff --git a/src/micropeak-v2.0/flash-loader/Makefile b/src/micropeak-v2.0/flash-loader/Makefile new file mode 100644 index 00000000..4e30c1c6 --- /dev/null +++ b/src/micropeak-v2.0/flash-loader/Makefile @@ -0,0 +1,8 @@ +# +# AltOS flash loader build +# +# + +TOPDIR=../.. +HARDWARE=micropeak-v2.0 +include $(TOPDIR)/stmf0/Makefile-flash.defs diff --git a/src/micropeak-v2.0/flash-loader/ao_pins.h b/src/micropeak-v2.0/flash-loader/ao_pins.h new file mode 100644 index 00000000..196a8b1d --- /dev/null +++ b/src/micropeak-v2.0/flash-loader/ao_pins.h @@ -0,0 +1,37 @@ +/* + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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_ + +#include <ao_flash_stm_pins.h> + +/* LED anode (PA2) to 3.3 for boot mode */ + +#define AO_BOOT_PIN			1 +#define AO_BOOT_APPLICATION_GPIO	stm_gpioa +#define AO_BOOT_APPLICATION_PIN		2 +#define AO_BOOT_APPLICATION_VALUE	0 +#define AO_BOOT_APPLICATION_MODE	AO_EXTI_MODE_PULL_DOWN + +/* USB */ +#define HAS_USB			1 +#define AO_USB_DIRECTIO		0 +#define AO_PA11_PA12_RMP	1 + +#endif /* _AO_PINS_H_ */ diff --git a/src/micropeak-v2.0/micropeak.ld b/src/micropeak-v2.0/micropeak.ld new file mode 100644 index 00000000..77717e16 --- /dev/null +++ b/src/micropeak-v2.0/micropeak.ld @@ -0,0 +1,123 @@ +/* + * 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; either version 2 of the License, or + * (at your option) any later version. + * + * 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. + */ + +MEMORY { +	rom (rx) :   ORIGIN = 0x08001000, LENGTH = 20K +	flash(rx) :  ORIGIN = 0x08006000, LENGTH = 8K +	ram (!w) :   ORIGIN = 0x20000000, LENGTH = 6k - 128 +	stack (!w) : ORIGIN = 0x20000000 + 6k - 128, LENGTH = 128 +} + +INCLUDE registers.ld + +EXTERN (stm_interrupt_vector) + +SECTIONS { +	/* +	 * Rom contents +	 */ + +	.interrupt ORIGIN(ram) : AT (ORIGIN(rom)) { +		__interrupt_start__ = .; +		__interrupt_rom__ = ORIGIN(rom); +		*(.interrupt)	/* Interrupt vectors */ +		__interrupt_end__ = .; +	} > ram + +	.text ORIGIN(rom) + 0x100 : { +		__text_start__ = .; + +		/* Ick. What I want is to specify the +		 * addresses of some global constants so +		 * that I can find them across versions +		 * of the application. I can't figure out +		 * how to make gnu ld do that, so instead +		 * we just load the two files that include +		 * these defines in the right order here and +		 * expect things to 'just work'. Don't change +		 * the contents of those files, ok? +		 */ +		ao_romconfig.o(.romconfig*) +		ao_product.o(.romconfig*) + +		*(.text*)	/* Executable code */ +	} > rom + +	.ARM.exidx : { +		*(.ARM.exidx* .gnu.linkonce.armexidx.*) +	} > rom + +	.rodata : { +		*(.rodata*)	/* Constants */ +	} > rom + +	__text_end__ = .; + +	/* Boot data which must live at the start of ram so that +	 * the application and bootloader share the same addresses. +	 * This must be all uninitialized data +	 */ +	.boot (NOLOAD) : { +		__boot_start__ = .; +		*(.boot) +		. = ALIGN(4); +		__boot_end__ = .; +	} >ram + +	/* Functions placed in RAM (required for flashing) +	 * +	 * Align to 8 bytes as that's what the ARM likes text +	 * segment alignments to be, and if we don't, then +	 * we end up with a mismatch between the location in +	 * ROM and the desired location in RAM. I don't +	 * entirely understand this, but at least this appears +	 * to work... +	 */ + +	.textram BLOCK(8): { +		__data_start__ = .; +		*(.ramtext) +	} >ram AT>rom + +	/* Data -- relocated to RAM, but written to ROM +	 */ +	.data : { +		*(.data)	/* initialized data */ +		. = ALIGN(4); +		__data_end__ = .; +	} >ram AT>rom + +	.bss : { +		__bss_start__ = .; +		*(.bss) +		*(COMMON) +		. = ALIGN(4); +		__bss_end__ = .; +	} >ram + +	PROVIDE(end = .); + +	PROVIDE(__flash__ = ORIGIN(flash)); +	PROVIDE(__flash_end__ = ORIGIN(flash) + LENGTH(flash)); + +	PROVIDE(__stack__ = ORIGIN(stack) + LENGTH(stack)); +} + +ENTRY(start); + + | 
