diff --git a/1_wire/Makefile b/1_wire/Makefile deleted file mode 100644 index ffe6748..0000000 --- a/1_wire/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = onewire -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103xB.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/1_wire/README b/1_wire/README deleted file mode 100644 index 472f619..0000000 --- a/1_wire/README +++ /dev/null @@ -1,8 +0,0 @@ -My approach to semi-hardware 1-wire realisation based on DMA+TIM2 - -written for chinese devboard based on STM32F103RBT6 - -Press H for help - -// Still some troubles left: for example, can't read ROM; also the code isn't fully done yet - diff --git a/1_wire/cdcacm.c b/1_wire/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/1_wire/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/1_wire/cdcacm.h b/1_wire/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/1_wire/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/1_wire/hardware_ini.c b/1_wire/hardware_ini.c deleted file mode 100644 index 8c80639..0000000 --- a/1_wire/hardware_ini.c +++ /dev/null @@ -1,98 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); - // test pin PC10: Push-Pull -#ifdef EBUG - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, GPIO10); -#endif -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -// check buttons S2/S3 -void check_btns(){ - static uint8_t oldstate[2] = {1,1}; // old buttons state - uint8_t newstate[2], i; - static uint32_t Old_timer[2] = {0,0}; - newstate[0] = gpio_get(BTNS_PORT, BTN_S2_PIN) ? 1 : 0; - newstate[1] = gpio_get(BTNS_PORT, BTN_S3_PIN) ? 1 : 0; - for(i = 0; i < 2; i++){ - uint8_t new = newstate[i]; - // pause for 60ms - uint32_t O = Old_timer[i]; - if(O){ - if(Timer - O > 60 || O > Timer){ - P("Button S"); - usb_send('2' + i); - if(new) P("released"); - else P("pressed"); - newline(); - oldstate[i] = new; - Old_timer[i] = 0; - } - } - else if(new != oldstate[i]){ - Old_timer[i] = Timer; - } - } -} diff --git a/1_wire/hardware_ini.h b/1_wire/hardware_ini.h deleted file mode 100644 index ff0311f..0000000 --- a/1_wire/hardware_ini.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * Buttons on devboard - */ -#define BTNS_PORT GPIOC -// PCO -- S2 -#define BTN_S2_PIN GPIO0 -// PC1 -- S3 -#define BTN_S3_PIN GPIO1 - -/* - * LEDS: PB9 for D1, PB8 for D2 - */ -#define LEDS_PORT GPIOB -#define LED_D1_PIN GPIO9 -#define LED_D2_PIN GPIO8 - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -void check_btns(); - -#endif // __HARDWARE_INI_H__ diff --git a/1_wire/ld/devices.data b/1_wire/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/1_wire/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/1_wire/ld/stm32f103x4.ld b/1_wire/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/1_wire/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103x6.ld b/1_wire/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/1_wire/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103x8.ld b/1_wire/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/1_wire/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xB.ld b/1_wire/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/1_wire/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xC.ld b/1_wire/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/1_wire/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xD.ld b/1_wire/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/1_wire/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xE.ld b/1_wire/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/1_wire/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xF.ld b/1_wire/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/1_wire/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/ld/stm32f103xG.ld b/1_wire/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/1_wire/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/1_wire/main.c b/1_wire/main.c deleted file mode 100644 index e7e2c7a..0000000 --- a/1_wire/main.c +++ /dev/null @@ -1,92 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "onewire.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - init_ow_dmatimer(); - - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - //check_and_parse_UART(USART1); // also check data in UART buffers - check_btns(); - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - OW_process(); - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/1_wire/main.h b/1_wire/main.h deleted file mode 100644 index 0cc7714..0000000 --- a/1_wire/main.h +++ /dev/null @@ -1,55 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/1_wire/onewire.bin b/1_wire/onewire.bin deleted file mode 100755 index daa1cbb..0000000 Binary files a/1_wire/onewire.bin and /dev/null differ diff --git a/1_wire/onewire.c b/1_wire/onewire.c deleted file mode 100644 index 2df4766..0000000 --- a/1_wire/onewire.c +++ /dev/null @@ -1,554 +0,0 @@ -/* - * onewire.c - functions to work with 1-wire devices - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#include "onewire.h" -#include "user_proto.h" - -OW_ID id_array[OW_MAX_NUM]; // 1-wire devices ID buffer (not more than eight) -uint8_t dev_amount = 0; // amount of 1-wire devices - - -// states of 1-wire processing queue -typedef enum{ - OW_OFF_STATE, // not working - OW_RESET_STATE, // reset bus - OW_SEND_STATE, // send data - OW_READ_STATE, // wait for reading -} OW_States; -volatile OW_States OW_State = OW_OFF_STATE; // 1-wire state, 0-not runned - -void (*ow_process_resdata)() = NULL; -void wait_reading(); - -uint16_t tim2_buff[TIM2_DMABUFF_SIZE]; -uint16_t tim2_inbuff[TIM2_DMABUFF_SIZE]; -int tum2buff_ctr = 0; -uint8_t ow_done = 1; -uint8_t ow_measurements_done = 0; - -/** - * this function sends bits of ow_byte (LSB first) to 1-wire line - * @param ow_byte - byte to convert - * @param Nbits - number of bits to send - * @param ini - 1 to zero counter - */ -uint8_t OW_add_byte(uint8_t ow_byte){ - uint8_t i, byte; - for(i = 0; i < 8; i++){ - if(ow_byte & 0x01){ - byte = BIT_ONE_P; - }else{ - byte = BIT_ZERO_P; - } - if(tum2buff_ctr == TIM2_DMABUFF_SIZE){ - ERR("Tim2 buffer overflow"); - return 0; // avoid buffer overflow - } - tim2_buff[tum2buff_ctr++] = byte; - ow_byte >>= 1; - } -// INT(tum2buff_ctr); -// DBG(" bytes in send buffer\n"); - return 1; -} - - - -/** - * Adds Nbytes bytes 0xff for reading sequence - */ -uint8_t OW_add_read_seq(uint8_t Nbytes){ - uint8_t i; - if(Nbytes == 0) return 0; - Nbytes *= 8; // 8 bits for each byte - for(i = 0; i < Nbytes; i++){ - if(tum2buff_ctr == TIM2_DMABUFF_SIZE){ - ERR("Tim2 buffer overflow"); - return 0; - } - tim2_buff[tum2buff_ctr++] = BIT_READ_P; - } -// INT(tum2buff_ctr); -// DBG(" bytes in send buffer\n"); - return 1; -} - -/** - * Fill output buffer with data from 1-wire - * @param start_idx - index from which to start (byte number) - * @param N - data length (in **bytes**) - * @outbuf - where to place data - */ -void read_from_OWbuf(uint8_t start_idx, uint8_t N, uint8_t *outbuf){ - start_idx *= 8; - uint8_t i, j, last = start_idx + N * 8, byte; - if(last >= TIM2_DMABUFF_SIZE) last = TIM2_DMABUFF_SIZE; - for(i = start_idx; i < last;){ - byte = 0; - for(j = 0; j < 8; j++){ - byte >>= 1; -// INT(tim2_inbuff[i]); -// DBG(" "); - if(tim2_inbuff[i++] < ONE_ZERO_BARRIER) - byte |= 0x80; - } - *outbuf++ = byte; -// DBG("readed \n"); - } -// print_hex(outbuf-N, N); -// DBG(" readed\n"); -} -// there's a mistake in opencm3, so redefine this if needed (TIM_CCMR2_CC3S_IN_TI1 -> TIM_CCMR2_CC3S_IN_TI4) -#ifndef TIM_CCMR2_CC3S_IN_TI4 -#define TIM_CCMR2_CC3S_IN_TI4 (2) -#endif -void init_ow_dmatimer(){ // tim2_ch4 - PA3, no remap - gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO3); - rcc_periph_clock_enable(RCC_TIM2); - rcc_periph_clock_enable(RCC_DMA1); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - // 36MHz of APB1 - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM2_PSC = 71; // prescaler is (div - 1) - TIM2_CR1 = TIM_CR1_ARPE; // bufferize ARR/CCR - TIM2_ARR = RESET_LEN; - // PWM_OUT: TIM2_CH4; capture: TIM2_CH3 - // PWM edge-aligned mode & enable preload for CCR4, CC3 takes input from TI4 - TIM2_CCMR2 = TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE | TIM_CCMR2_CC3S_IN_TI4; - TIM2_CCR4 = 0; // set output value to 1 by clearing CCR4 - TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4 - // set low polarity for CC4, high for CC3 & enable CC4 out and CC3 in - TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; - - // TIM2_CH4 - DMA1, channel 7 - dma_channel_reset(DMA1, DMA_CHANNEL7); - DMA1_CCR7 = DMA_CCR_DIR | DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT - | DMA_CCR_TEIE | DMA_CCR_TCIE | DMA_CCR_PL_HIGH; - nvic_enable_irq(NVIC_DMA1_CHANNEL7_IRQ); // enable dma1_channel7_isr - tum2buff_ctr = 0; - DBG("OW INITED\n"); -#ifdef EBUG - gpio_set(GPIOC, GPIO10); -#endif -} - -void run_dmatimer(){ - ow_done = 0; - TIM2_CR1 = 0; - adc_disable_dma(ADC1); // turn off DMA & ADC - adc_off(ADC1); - // TIM2_CH4 - DMA1, channel 7 - DMA1_IFCR = DMA_ISR_TEIF7|DMA_ISR_HTIF7|DMA_ISR_TCIF7|DMA_ISR_GIF7 | - DMA_ISR_TEIF1|DMA_ISR_HTIF1|DMA_ISR_TCIF1|DMA_ISR_GIF1; // clear flags - DMA1_CCR7 &= ~DMA_CCR_EN; // disable (what if it's enabled?) to set address - DMA1_CPAR7 = (uint32_t) &(TIM_CCR4(TIM2)); // dma_set_peripheral_address(DMA1, DMA_CHANNEL7, (uint32_t) &(TIM_CCR4(TIM2))); - DMA1_CMAR7 = (uint32_t) &tim2_buff[1]; // dma_set_memory_address(DMA1, DMA_CHANNEL7, (uint32_t)tim2_buff); - DMA1_CNDTR7 = tum2buff_ctr-1;//dma_set_number_of_data(DMA1, DMA_CHANNEL7, tum2buff_ctr); - // TIM2_CH3 - DMA1, channel 1 - dma_channel_reset(DMA1, DMA_CHANNEL1); - DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT - | DMA_CCR_TEIE | DMA_CCR_TCIE | DMA_CCR_PL_HIGH; - DMA1_CPAR1 = (uint32_t) &(TIM_CCR3(TIM2)); //dma_set_peripheral_address(DMA1, DMA_CHANNEL1, (uint32_t) &(TIM_CCR3(TIM2))); - DMA1_CMAR1 = (uint32_t) tim2_inbuff; //dma_set_memory_address(DMA1, DMA_CHANNEL1, (uint32_t) tim2_inbuff); - DMA1_CNDTR1 = tum2buff_ctr; //dma_set_number_of_data(DMA1, DMA_CHANNEL1, tum2buff_ctr); - nvic_enable_irq(NVIC_DMA1_CHANNEL1_IRQ); - - DMA1_CCR7 |= DMA_CCR_EN; //dma_enable_channel(DMA1, DMA_CHANNEL7); - DMA1_CCR1 |= DMA_CCR_EN; //dma_enable_channel(DMA1, DMA_CHANNEL1); - - TIM2_SR = 0; // clear all flags - TIM2_ARR = BIT_LEN; // bit length - TIM2_CCR4 = tim2_buff[0]; // we should manually set first bit to avoid zero in tim2_inbuff[0] - TIM2_EGR = TIM_EGR_UG; // update value of ARR - TIM2_CR1 = TIM_CR1_ARPE; // bufferize ARR/CCR - - TIM2_CR2 &= ~TIM_CR2_CCDS; // timer_set_dma_on_compare_event(TIM2); - TIM2_DIER = TIM_DIER_CC4DE | TIM_DIER_CC3DE; // enable DMA events - // set low polarity, enable cc out & enable input capture - TIM2_CR1 |= TIM_CR1_CEN; // run timer -#ifdef EBUG - gpio_clear(GPIOC, GPIO10); -#endif -/* DBG("RUN transfer of "); - INT(tum2buff_ctr); - DBG(" bits\n");*/ -} - -uint16_t rstat = 0, lastcc3 = 3; -void ow_reset(){ - //init_ow_dmatimer(); - ow_done = 0; - rstat = 0; - TIM2_SR = 0; // clear all flags - TIM2_CR1 = 0; - TIM2_DIER = 0; // disable timer interrupts - TIM2_ARR = RESET_LEN; // set period to 1ms - TIM2_CCR4 = RESET_P; // zero pulse length - TIM2_EGR = TIM_EGR_UG; // update values of ARR & CCR4 - //TIM2_CCMR2 = TIM_CCMR2_OC4M_PWM1 | TIM_CCMR2_OC4PE | TIM_CCMR2_CC3S_IN_TI4; - //TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; -// DBG("OW RESET in process"); - TIM2_DIER = TIM_DIER_CC3IE; -#ifdef EBUG - gpio_clear(GPIOC, GPIO10); -#endif - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN | TIM_CR1_UDIS; // we need only single pulse & run timer; disable UEV - TIM2_SR = 0; // clear update flag generated after timer's running - nvic_enable_irq(NVIC_TIM2_IRQ); -} - -void tim2_isr(){ - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - TIM2_DIER = 0; // disable all timer interrupts -#ifdef EBUG - gpio_set(GPIOC, GPIO10); -#endif - TIM2_CCR4 = 0; // set output value to 1 - TIM2_SR = 0; // clear flag - nvic_disable_irq(NVIC_TIM2_IRQ); - ow_done = 1; - rstat = lastcc3; -// DBG(" ... done!\n"); - } - if(TIM2_SR & TIM_SR_CC3IF){ // we need this interrupt to store CCR3 value - lastcc3 = TIM2_CCR3; - TIM2_CR1 &= ~TIM_CR1_UDIS; // enable UEV - TIM2_SR = 0; // clear flag (we've manage TIM_SR_UIF before, so can simply do =0) - TIM2_DIER |= TIM_DIER_UIE; // Now allow also Update interrupts to turn off everything - } -} - -/** - * DMA interrupt in 1-wire mode - */ -void dma1_channel1_isr(){ - // int i; - if(DMA1_ISR & DMA_ISR_TCIF1){ -#ifdef EBUG - gpio_set(GPIOC, GPIO10); -#endif - DMA1_IFCR = DMA_IFCR_CTCIF1; - TIM2_CR1 &= ~TIM_CR1_CEN; // timer_disable_counter(TIM2); - DMA1_CCR1 &= ~DMA_CCR_EN; // disable DMA1 channel 1 - nvic_disable_irq(NVIC_DMA1_CHANNEL1_IRQ); - ow_done = 1; -/* for(i = 0; i < tum2buff_ctr; i++){ - print_int(tim2_inbuff[i]); - P(" "); - } - P("\n");*/ - }else if(DMA1_ISR & DMA_ISR_TEIF1){ - DMA1_IFCR = DMA_IFCR_CTEIF1; - DBG("DMA in transfer error\n"); - } -} - -void dma1_channel7_isr(){ - if(DMA1_ISR & DMA_ISR_TCIF7){ - DMA1_IFCR = DMA_IFCR_CTCIF7; // clear flag - DMA1_CCR7 &= ~DMA_CCR_EN; // disable DMA1 channel 7 - }else if(DMA1_ISR & DMA_ISR_TEIF7){ - DMA1_IFCR = DMA_IFCR_CTEIF7; - DBG("DMA out transfer error\n"); - } -} - - -uint8_t OW_get_reset_status(){ - if(rstat < RESET_BARRIER) return 0; // no devices - return 1; -} - - -uint8_t ow_data_ready = 0; // flag of reading OK - -/** - * Process 1-wire commands depending on its state - */ -void OW_process(){ - static uint8_t ow_was_reseting = 0; - switch(OW_State){ - case OW_OFF_STATE: - return; - break; - case OW_RESET_STATE: - //DBG("OW reset\n"); - OW_State = OW_SEND_STATE; - ow_was_reseting = 1; - ow_reset(); - break; - case OW_SEND_STATE: - if(!ow_done) return; // reset in work - if(ow_was_reseting){ - if(rstat < RESET_BARRIER){ - ERR("Error: no 1-wire devices found"); - INT(rstat); - DBG("\n"); - ow_was_reseting = 0; - OW_State = OW_OFF_STATE; - return; - } - } - ow_was_reseting = 0; - OW_State = OW_READ_STATE; - run_dmatimer(); // turn on data transfer - //DBG("OW send\n"); - break; - case OW_READ_STATE: - if(!ow_done) return; // data isn't ready - OW_State = OW_OFF_STATE; - // adc_dma_on(); // return DMA1_1 to ADC at end of data transmitting - if(ow_process_resdata) - ow_process_resdata(); - ow_data_ready = 1; - //DBG("OW read\n"); - break; - } -} - - -uint8_t *read_buf = NULL; // buffer for storing readed data -/** - * fill ID buffer with readed data - */ -void fill_buff_with_data(){ - ow_process_resdata = NULL; - if(!read_buf) return; - read_from_OWbuf(1, 8, read_buf); - int i, j; - P("Readed ID: "); - for(i = 0; i < 8; ++i){ - print_hex(&read_buf[i], 1); - usb_send(' '); - } - usb_send('\n'); - // now check stored ROMs - for(i = 0; i < dev_amount; ++i){ - uint8_t *ROM = id_array[i].bytes; - for(j = 0; j < 8; j++) - if(ROM[j] != read_buf[j]) break; - if(j == 8){ // we found this cell - DBG("Such ID exists\n"); - goto ret; - } - } - ++dev_amount; -ret: - read_buf = NULL; -} - -/** - * fill Nth array with identificators - */ -//uint8_t comtosend = 0; -void OW_fill_next_ID(){ - if(dev_amount >= OW_MAX_NUM){ - ERR("No memory left for new device\n"); - return; - } - ow_data_ready = 0; - OW_State = OW_RESET_STATE; - OW_reset_buffer(); - OW_add_byte(OW_READ_ROM); - OW_add_read_seq(8); // wait for 8 bytes - read_buf = id_array[dev_amount].bytes; - ow_process_resdata = fill_buff_with_data; - DBG("wait for ID\n"); -} - -/** - * Procedure of 1-wire communications - * variables: - * @param sendReset - send RESET before transmission - * @param command - bytes sent to the bus (if we want to read, send OW_READ_SLOT) - * @param cLen - command buffer length (how many bytes to send) - * @return 1 if succeed, 0 if failure - */ -uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen){ - ow_data_ready = 0; - // if reset needed - send RESET and check bus - if(sendReset) - OW_State = OW_RESET_STATE; - else - OW_State = OW_SEND_STATE; - OW_reset_buffer(); - while(cLen-- > 0){ - if(!OW_add_byte(*command++)) return 0; - } - return 1; -} - -/** - * convert temperature from scratchpad - * in case of error return 200000 (ERR_TEMP_VAL) - * return value in 10th degrees centigrade - * - * 0 - themperature LSB - * 1 - themperature MSB (all higher bits are sign) - * 2 - T_H - * 3 - T_L - * 4 - B20: Configuration register (only bits 6/5 valid: 9..12 bits resolution); 0xff for S20 - * 5 - 0xff (reserved) - * 6 - (reserved for B20); S20: COUNT_REMAIN (0x0c) - * 7 - COUNT PER DEGR (0x10) - * 8 - CRC - */ -int32_t gettemp(uint8_t *scratchpad){ - // detect DS18S20 - int32_t t = 0; - uint8_t l,m; - int8_t v; - if(scratchpad[7] == 0xff) // 0xff can be only if there's no such device or some other error - return ERR_TEMP_VAL; - m = scratchpad[1]; - l = scratchpad[0]; - if(scratchpad[4] == 0xff){ // DS18S20 - v = l >> 1 | (m & 0x80); // take signum from MSB - t = ((int32_t)v) * 10L; - if(l&1) t += 5L; // decimal 0.5 - }else{ // DS18B20 - v = l>>4 | ((m & 7)<<4) | (m & 0x80); - t = ((int32_t)v) * 10L; - m = (l & 0x0f) >> 1; // add decimal - // 0 0 1 1 2 2 3 3 4 4 5 5 6 6 7 7 -> - // 0 1 1 2 3 3 4 4 5 6 6 7 8 8 9 9 - t += (int32_t)m; // t = v*10 + l*0.625 -> convert - if(m) ++t; // 1->1, 2->3, 3->4, 4->5, 5->6 - if(m > 5) ++t; // 6->8, 7->9 - } - return t; -} - -int32_t temperature = ERR_TEMP_VAL; -int8_t Ncur = 0; -/** - * get temperature from buffer - */ -void convert_next_temp(){ - uint8_t scratchpad[9]; - ow_process_resdata = NULL; - if(dev_amount < 2){ - read_from_OWbuf(2, 9, scratchpad); - }else{ - read_from_OWbuf(10, 9, scratchpad); - } - temperature = gettemp(scratchpad); - DBG("Readed temperature: "); - INT(temperature); - DBG("/10 degrC\n"); -} - -/** - * read next stored thermometer - */ -void OW_read_next_temp(){ - ow_data_ready = 0; - OW_State = OW_RESET_STATE; - OW_reset_buffer(); - int i; - if(dev_amount < 2){ - Ncur = -1; - OW_add_byte(OW_SKIP_ROM); - }else{ - if(++Ncur >= dev_amount) Ncur = 0; - OW_add_byte(OW_MATCH_ROM); - uint8_t *ROM = id_array[Ncur].bytes; - for(i = 0; i < 8; ++i) - OW_add_byte(ROM[i]); - } - OW_add_byte(OW_READ_SCRATCHPAD); - OW_add_read_seq(9); // wait for 9 bytes - ROM - ow_process_resdata = convert_next_temp; -} - -void wait_reading(){ - uint8_t bt; - read_from_OWbuf(0, 1, &bt); - if(bt == 0xff){ // the conversion is done! - ow_measurements_done = 1; - ow_process_resdata = NULL; - DBG("Measurements done!\n"); - }else{ - OW_State = OW_SEND_STATE; - OW_reset_buffer(); - ow_data_ready = 0; - OW_add_read_seq(1); // send read seq waiting for end of conversion - } -} - -void OW_send_read_seq(){ - ow_data_ready = 0; - ow_measurements_done = 0; - OW_State = OW_RESET_STATE; - OW_reset_buffer(); - OW_add_byte(OW_SKIP_ROM); - OW_add_byte(OW_CONVERT_T); - OW_add_read_seq(1); // send read seq waiting for end of conversion - ow_process_resdata = wait_reading; -} -/* - * scan 1-wire bus - * WARNING! The procedure works in real-time, so it is VERY LONG - * num - max number of devices - * buf - array for devices' ID's (8*num bytes) - * return amount of founded devices - * -uint8_t OW_Scan(uint8_t *buf, uint8_t num){ - unsigned long path,next,pos; - uint8_t bit,chk; - uint8_t cnt_bit, cnt_byte, cnt_num; - path=0; - cnt_num=0; - do{ - //(issue the 'ROM search' command) - if( 0 == OW_WriteCmd(OW_SEARCH_ROM) ) return 0; - OW_Wait_TX(); - OW_ClearBuff(); // clear RX buffer - next = 0; // next path to follow - pos = 1; // path bit pointer - for(cnt_byte = 0; cnt_byte != 8; cnt_byte++){ - buf[cnt_num*8 + cnt_byte] = 0; - for(cnt_bit = 0; cnt_bit != 8; cnt_bit++){ - //(read two bits, 'bit' and 'chk', from the 1-wire bus) - OW_SendBits(OW_R, 2); - OW_Wait_TX(); - bit = -----OW_ReadByte(); - chk = bit & 0x02; // bit 1 - bit = bit & 0x01; // bit 0 - if(bit && chk) return 0; // error - if(!bit && !chk){ // collision, both are zero - if (pos & path) bit = 1; // if we've been here before - else next = (path&(pos-1)) | pos; // else, new branch for next - pos <<= 1; - } - //(save this bit as part of the current ROM value) - if (bit) buf[cnt_num*8 + cnt_byte]|=(1<550 if there's devices on line (on reset), >12 (typ.15) - read 0, < 12 (typ.1) - read 1 -#define RESET_LEN ((uint16_t)1000) -#define BIT_LEN ((uint16_t)100) -#define RESET_P ((uint16_t)500) -#define BIT_ONE_P ((uint16_t)10) -#define BIT_ZERO_P ((uint16_t)60) -#define BIT_READ_P ((uint16_t)5) -#define RESET_BARRIER ((uint16_t)550) -#define ONE_ZERO_BARRIER ((uint16_t)10) - -#define ERR_TEMP_VAL ((int32_t)200000) - -typedef struct{ - uint8_t bytes[8]; -} OW_ID; - -extern OW_ID id_array[]; - -#define OW_MAX_NUM 8 - -void init_ow_dmatimer(); -void run_dmatimer(); -extern uint8_t ow_done; -#define OW_READY() (ow_done) -void ow_dma_on(); -uint8_t OW_add_byte(uint8_t ow_byte); -uint8_t OW_add_read_seq(uint8_t Nbytes); -void read_from_OWbuf(uint8_t start_idx, uint8_t N, uint8_t *outbuf); -void ow_reset(); -uint8_t OW_get_reset_status(); - -extern int tum2buff_ctr; -#define OW_reset_buffer() do{tum2buff_ctr = 0;}while(0) - -extern uint8_t ow_data_ready; -extern uint8_t ow_measurements_done; -#define OW_DATA_READY() (ow_data_ready) -#define OW_CLEAR_READY_FLAG() do{ow_data_ready = 0;}while(0) -#define OW_MEASUREMENTS_DONE() (ow_measurements_done) -#define OW_CLEAR_DONE_FLAG() do{ow_measurements_done = 0;}while(0) - -void OW_process(); -void OW_fill_next_ID(); -void OW_send_read_seq(); -uint8_t OW_Send(uint8_t sendReset, uint8_t *command, uint8_t cLen); - -extern int32_t temperature; -extern int8_t Ncur; -void OW_read_next_temp(); -#define OW_current_temp() (temperature) -#define OW_current_num() (Ncur) - -/* - * thermometer commands - * send them with bus reset! - */ -// find devices -#define OW_SEARCH_ROM (0xf0) -// read device (when it is alone on the bus) -#define OW_READ_ROM (0x33) -// send device ID (after this command - 8 bytes of ID) -#define OW_MATCH_ROM (0x55) -// broadcast command -#define OW_SKIP_ROM (0xcc) -// find devices with critical conditions -#define OW_ALARM_SEARCH (0xec) -/* - * thermometer functions - * send them without bus reset! - */ -// start themperature reading -#define OW_CONVERT_T (0x44) -// write critical temperature to device's RAM -#define OW_SCRATCHPAD (0x4e) -// read whole device flash -#define OW_READ_SCRATCHPAD (0xbe) -// copy critical themperature from device's RAM to its EEPROM -#define OW_COPY_SCRATCHPAD (0x48) -// copy critical themperature from EEPROM to RAM (when power on this operation runs automatically) -#define OW_RECALL_E2 (0xb8) -// check whether there is devices wich power up from bus -#define OW_READ_POWER_SUPPLY (0xb4) - - -/* - * thermometer identificator is: 8bits CRC, 48bits serial, 8bits device code (10h) - * Critical temperatures is T_H and T_L - * T_L is lowest allowed temperature - * T_H is highest -//- - * format T_H and T_L: 1bit sigh + 7bits of data - */ - - -/* - * RAM register: - * 0 - themperature: 1 ADU == 0.5 degrC - * 1 - sign (0 - T>0 degrC ==> T=byte0; 1 - T<0 degrC ==> T=byte0-0xff+1) - * 2 - T_H - * 3 - T_L - * 4 - 0xff (reserved) - * 5 - 0xff (reserved) - * 6 - COUNT_REMAIN (0x0c) - * 7 - COUNT PER DEGR (0x10) - * 8 - CRC - */ - - -#endif // __ONEWIRE_H__ diff --git a/1_wire/sync.c b/1_wire/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/1_wire/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/1_wire/sync.h b/1_wire/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/1_wire/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/1_wire/user_proto.c b/1_wire/user_proto.c deleted file mode 100644 index 5376f39..0000000 --- a/1_wire/user_proto.c +++ /dev/null @@ -1,243 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "onewire.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("H\tshow this help\n"); - P("I\ttest entering integer value\n"); - P("T\tshow current approx. time\n"); - P("1\tswitch LED D1 state\n"); - P("2\tswitch LED D2 state\n"); - P("R\tstart reading temperature\n"); - P("P\tread DS18 ID\n"); - P("Q\tget temperature\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case '1': - gpio_toggle(LEDS_PORT, LED_D1_PIN); - break; - case '2': - gpio_toggle(LEDS_PORT, LED_D2_PIN); - break; - case 'H': // show help - help(); - break; - case 'I': // enter integer & show its value - I = show_int; - READINT(); - break; - case 'T': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case 'P': - OW_fill_next_ID(); - break; - case 'Q': - if(OW_MEASUREMENTS_DONE()) - OW_read_next_temp(); - else - P("Wait for measurements ends or start another\n"); - break; - case 'R': - OW_send_read_seq(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -void ERR(char *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*((uint8_t*)wrd++)); - usb_send('\n'); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - -void OW_printID(uint8_t N){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - int i; - uint8_t *b = id_array[N].bytes; - usb_send('0'); usb_send('x'); // prefix 0x - for(i = 0; i < 8; i++){ - putc(b[i] >> 4); - putc(b[i] & 0x0f); - } - usb_send('\n'); -} diff --git a/1_wire/user_proto.h b/1_wire/user_proto.h deleted file mode 100644 index 24dc159..0000000 --- a/1_wire/user_proto.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) - #define INT(N) do{print_int(N);}while(0) -#else - #define DBG(a) - #define INT(N) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void ERR(char *wrd); -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); -void OW_printID(uint8_t N); - -#endif // __USER_PROTO_H__ diff --git a/DMA_GPIO/Makefile b/DMA_GPIO/Makefile deleted file mode 100644 index df889ac..0000000 --- a/DMA_GPIO/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = dma_gpio -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/DMA_GPIO/README b/DMA_GPIO/README deleted file mode 100644 index 65237d6..0000000 --- a/DMA_GPIO/README +++ /dev/null @@ -1 +0,0 @@ -simple 8-bit FSMC emulation with DMA diff --git a/DMA_GPIO/cdcacm.c b/DMA_GPIO/cdcacm.c deleted file mode 100644 index e694f69..0000000 --- a/DMA_GPIO/cdcacm.c +++ /dev/null @@ -1,310 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -uint8_t usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/DMA_GPIO/cdcacm.h b/DMA_GPIO/cdcacm.h deleted file mode 100644 index 977167f..0000000 --- a/DMA_GPIO/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern uint8_t usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/DMA_GPIO/dma_gpio.bin b/DMA_GPIO/dma_gpio.bin deleted file mode 100755 index d93f1a0..0000000 Binary files a/DMA_GPIO/dma_gpio.bin and /dev/null differ diff --git a/DMA_GPIO/dmagpio.c b/DMA_GPIO/dmagpio.c deleted file mode 100644 index 5c170d9..0000000 --- a/DMA_GPIO/dmagpio.c +++ /dev/null @@ -1,97 +0,0 @@ -/* - * dmagpio.c - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "dmagpio.h" -#include "user_proto.h" - -int transfer_complete = 0; -static uint16_t gpiobuff[128] = {0}; - -void dmagpio_init(){ - // init TIM2 & DMA1ch2 (TIM2UP) - rcc_periph_clock_enable(RCC_TIM2); - rcc_periph_clock_enable(RCC_DMA1); - timer_reset(TIM2); - // timer have frequency of 1MHz - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 18 = 4MHz - TIM2_PSC = 0; // prescaler is (div - 1) - TIM2_ARR = 1; // 36MHz (6.25) - TIM2_DIER = TIM_DIER_UDE;// | TIM_DIER_UIE; -//nvic_enable_irq(NVIC_TIM2_IRQ); - - dma_channel_reset(DMA1, DMA_CHANNEL2); - // mem2mem, medium prio, 8bits, memory increment, read from mem, transfer complete en - //DMA1_CCR2 = DMA_CCR_MEM2MEM | DMA_CCR_PL_MEDIUM | DMA_CCR_MSIZE_16BIT | - DMA1_CCR2 = DMA_CCR_PL_MEDIUM | DMA_CCR_MSIZE_16BIT | - DMA_CCR_PSIZE_16BIT | DMA_CCR_MINC | DMA_CCR_DIR | DMA_CCR_TCIE | DMA_CCR_TEIE ; - nvic_enable_irq(NVIC_DMA1_CHANNEL2_IRQ); - // target address: - DMA1_CPAR2 = DMAGPIO_TARGADDR; - DMA1_CMAR2 = (uint32_t) gpiobuff; -} -/* -void tim2_isr(){ - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - ++cntr; - GPIOA_ODR = gpiobuff[curidx]; - if(++curidx >= len){ - TIM2_CR1 &= ~TIM_CR1_CEN; - transfer_complete = 1; - } - TIM2_SR = 0; - } -} -*/ - -void dmagpio_transfer(uint8_t *databuf, uint32_t length){ - while(DMA1_CCR2 & DMA_CCR_EN); - transfer_complete = 0; - DMA1_IFCR = 0xff00; // clear all flags for ch2 - // memory address - //DMA1_CMAR2 = (uint32_t) databuf; - // buffer length -// DMA1_CPAR2 = DMAGPIO_TARGADDR; -// DMA1_CMAR2 = (uint32_t) gpiobuff; - DMA1_CNDTR2 = length; - uint32_t i; - for(i = 0; i < length; ++i) gpiobuff[i] = databuf[i]; - TIM2_CR1 |= TIM_CR1_CEN; // run timer - DMA1_CCR2 |= DMA_CCR_EN; -} - -void dma1_channel2_isr(){ - if(DMA1_ISR & DMA_ISR_TCIF2){ - transfer_complete = 1; - // stop timer & turn off DMA - TIM2_CR1 &= ~TIM_CR1_CEN; - DMA1_CCR2 &= ~DMA_CCR_EN; - DMA1_IFCR = DMA_IFCR_CTCIF2; // clear flag - /* uint32_t arr = TIM2_ARR; - if(arr == 1) TIM2_ARR = 71; - else TIM2_ARR = arr - 1;*/ - }else if(DMA1_ISR & DMA_ISR_TEIF2){ - P("Error\n"); - DMA1_IFCR = DMA_IFCR_CTEIF2; - TIM2_CR1 &= ~TIM_CR1_CEN; - DMA1_CCR2 &= ~DMA_CCR_EN; - } -} diff --git a/DMA_GPIO/dmagpio.h b/DMA_GPIO/dmagpio.h deleted file mode 100644 index 5ee0605..0000000 --- a/DMA_GPIO/dmagpio.h +++ /dev/null @@ -1,32 +0,0 @@ -/* - * dmagpio.h - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __DMAGPIO_H__ -#define __DMAGPIO_H__ - -#include "main.h" -#include "hardware_ini.h" - -void dmagpio_init(); -void dmagpio_transfer(uint8_t *databuf, uint32_t length); -extern int transfer_complete; - -#endif // __DMAGPIO_H__ diff --git a/DMA_GPIO/hardware_ini.c b/DMA_GPIO/hardware_ini.c deleted file mode 100644 index 3c8e136..0000000 --- a/DMA_GPIO/hardware_ini.c +++ /dev/null @@ -1,72 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - // DMAGPIO - gpio_set_mode(DMAGPIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, - DMAGPIO_PINS); - - /* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); - */ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} diff --git a/DMA_GPIO/hardware_ini.h b/DMA_GPIO/hardware_ini.h deleted file mode 100644 index 0059a3c..0000000 --- a/DMA_GPIO/hardware_ini.h +++ /dev/null @@ -1,65 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * DMA to GPIO port & pins (mask) - */ -#define DMAGPIO_PORT GPIOA -#define DMAGPIO_PINS 0xff -#define DMAGPIO_TARGADDR ((uint32_t)&(GPIOA_ODR)) - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/DMA_GPIO/ld/devices.data b/DMA_GPIO/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/DMA_GPIO/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/DMA_GPIO/ld/stm32f103x4.ld b/DMA_GPIO/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/DMA_GPIO/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103x6.ld b/DMA_GPIO/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/DMA_GPIO/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103x8.ld b/DMA_GPIO/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/DMA_GPIO/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xB.ld b/DMA_GPIO/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/DMA_GPIO/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xC.ld b/DMA_GPIO/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/DMA_GPIO/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xD.ld b/DMA_GPIO/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/DMA_GPIO/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xE.ld b/DMA_GPIO/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/DMA_GPIO/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xF.ld b/DMA_GPIO/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/DMA_GPIO/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/ld/stm32f103xG.ld b/DMA_GPIO/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/DMA_GPIO/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/DMA_GPIO/main.c b/DMA_GPIO/main.c deleted file mode 100644 index 131a6f0..0000000 --- a/DMA_GPIO/main.c +++ /dev/null @@ -1,90 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "dmagpio.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - dmagpio_init(); - - usb_connect(); // turn on USB - - int oldusblen = 0; - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen != oldusblen){ // there's something in USB buffer - parse_incoming_buf(usbdatabuf, &usbdatalen); - oldusblen = usbdatalen; - } - if(transfer_complete){ - P("transfered\n"); - transfer_complete = 0; - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/DMA_GPIO/main.h b/DMA_GPIO/main.h deleted file mode 100644 index 3a781a0..0000000 --- a/DMA_GPIO/main.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/DMA_GPIO/sync.c b/DMA_GPIO/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/DMA_GPIO/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/DMA_GPIO/sync.h b/DMA_GPIO/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/DMA_GPIO/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/DMA_GPIO/user_proto.c b/DMA_GPIO/user_proto.c deleted file mode 100644 index 09c1870..0000000 --- a/DMA_GPIO/user_proto.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "dmagpio.h" - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -void parse_incoming_buf(uint8_t *buf, int *len){ - static int lastidx = 0; - int l = *len; - for(; lastidx < l; ++lastidx){ - uint8_t cmd = buf[lastidx]; - usb_send(cmd); - if(cmd == '\n'){ - dmagpio_transfer(buf, *len); - *len = 0; - lastidx = 0; - return; - } - } -} - -/** - * Send char array wrd thru USB - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/DMA_GPIO/user_proto.h b/DMA_GPIO/user_proto.h deleted file mode 100644 index 3835098..0000000 --- a/DMA_GPIO/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -void parse_incoming_buf(uint8_t *buf, int *len); - -#endif // __USER_PROTO_H__ diff --git a/GPIO_TIM/Makefile b/GPIO_TIM/Makefile deleted file mode 100644 index d2275ad..0000000 --- a/GPIO_TIM/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = tim_gpio -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/GPIO_TIM/README b/GPIO_TIM/README deleted file mode 100644 index 8709cb9..0000000 --- a/GPIO_TIM/README +++ /dev/null @@ -1 +0,0 @@ -simple FSMC emulation by timer interrupts diff --git a/GPIO_TIM/cdcacm.c b/GPIO_TIM/cdcacm.c deleted file mode 100644 index e694f69..0000000 --- a/GPIO_TIM/cdcacm.c +++ /dev/null @@ -1,310 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -uint8_t usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/GPIO_TIM/cdcacm.h b/GPIO_TIM/cdcacm.h deleted file mode 100644 index 977167f..0000000 --- a/GPIO_TIM/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern uint8_t usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/GPIO_TIM/hardware_ini.c b/GPIO_TIM/hardware_ini.c deleted file mode 100644 index 3eefee9..0000000 --- a/GPIO_TIM/hardware_ini.c +++ /dev/null @@ -1,60 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - // DMAGPIO - gpio_set_mode(DMAGPIO_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL, - DMAGPIO_PINS); - -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} diff --git a/GPIO_TIM/hardware_ini.h b/GPIO_TIM/hardware_ini.h deleted file mode 100644 index aafe0f5..0000000 --- a/GPIO_TIM/hardware_ini.h +++ /dev/null @@ -1,65 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * DMA to GPIO port & pins (mask) - */ -#define DMAGPIO_PORT GPIOA -#define DMAGPIO_PINS 0xff -#define DMAGPIO_TARGADDR GPIOA_ODR - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/GPIO_TIM/ld/devices.data b/GPIO_TIM/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/GPIO_TIM/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/GPIO_TIM/ld/stm32f103x4.ld b/GPIO_TIM/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/GPIO_TIM/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103x6.ld b/GPIO_TIM/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/GPIO_TIM/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103x8.ld b/GPIO_TIM/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/GPIO_TIM/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xB.ld b/GPIO_TIM/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/GPIO_TIM/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xC.ld b/GPIO_TIM/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/GPIO_TIM/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xD.ld b/GPIO_TIM/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/GPIO_TIM/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xE.ld b/GPIO_TIM/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/GPIO_TIM/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xF.ld b/GPIO_TIM/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/GPIO_TIM/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/ld/stm32f103xG.ld b/GPIO_TIM/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/GPIO_TIM/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPIO_TIM/main.c b/GPIO_TIM/main.c deleted file mode 100644 index 4cb5fd2..0000000 --- a/GPIO_TIM/main.c +++ /dev/null @@ -1,90 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "timgpio.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - timgpio_init(); - - usb_connect(); // turn on USB - - int oldusblen = 0; - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen != oldusblen){ // there's something in USB buffer - parse_incoming_buf(usbdatabuf, &usbdatalen); - oldusblen = usbdatalen; - } - if(transfer_complete){ - P("transfered\n"); - transfer_complete = 0; - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/GPIO_TIM/main.h b/GPIO_TIM/main.h deleted file mode 100644 index 3a781a0..0000000 --- a/GPIO_TIM/main.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/GPIO_TIM/sync.c b/GPIO_TIM/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/GPIO_TIM/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/GPIO_TIM/sync.h b/GPIO_TIM/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/GPIO_TIM/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/GPIO_TIM/tim_gpio.bin b/GPIO_TIM/tim_gpio.bin deleted file mode 100755 index 8daa94c..0000000 Binary files a/GPIO_TIM/tim_gpio.bin and /dev/null differ diff --git a/GPIO_TIM/timgpio.c b/GPIO_TIM/timgpio.c deleted file mode 100644 index c8f6ed9..0000000 --- a/GPIO_TIM/timgpio.c +++ /dev/null @@ -1,61 +0,0 @@ -/* - * timgpio.c - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "timgpio.h" -#include "user_proto.h" - -int transfer_complete = 0; -static uint8_t addr[128]; -static uint32_t len = 0, curidx = 0; - -void timgpio_init(){ - // init TIM2 & DMA1ch2 (TIM2UP) - rcc_periph_clock_enable(RCC_TIM2); - rcc_periph_clock_enable(RCC_DMA1); - timer_reset(TIM2); - // timer have frequency of 1MHz - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz main freq, 2MHz for timer - TIM2_PSC = 0; - TIM2_ARR = 35; - TIM2_DIER = TIM_DIER_UDE | TIM_DIER_UIE; - nvic_enable_irq(NVIC_TIM2_IRQ); -} - -void tim2_isr(){ - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - GPIOA_ODR = addr[curidx]; - if(++curidx >= len){ - TIM2_CR1 &= ~TIM_CR1_CEN; - transfer_complete = 1; - } - TIM2_SR = 0; - } -} - - -void timgpio_transfer(uint8_t *databuf, uint32_t length){ - transfer_complete = 0; - memcpy(addr, databuf, length); - len = length; - curidx = 0; - TIM2_CR1 |= TIM_CR1_CEN; // run timer -} diff --git a/GPIO_TIM/timgpio.h b/GPIO_TIM/timgpio.h deleted file mode 100644 index b11d649..0000000 --- a/GPIO_TIM/timgpio.h +++ /dev/null @@ -1,32 +0,0 @@ -/* - * timpio.h - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __DMAGPIO_H__ -#define __DMAGPIO_H__ - -#include "main.h" -#include "hardware_ini.h" - -void timgpio_init(); -void timgpio_transfer(uint8_t *databuf, uint32_t length); -extern int transfer_complete; - -#endif // __DMAGPIO_H__ diff --git a/GPIO_TIM/user_proto.c b/GPIO_TIM/user_proto.c deleted file mode 100644 index cb48c67..0000000 --- a/GPIO_TIM/user_proto.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "timgpio.h" - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -void parse_incoming_buf(uint8_t *buf, int *len){ - static int lastidx = 0; - int l = *len; - for(; lastidx < l; ++lastidx){ - uint8_t cmd = buf[lastidx]; - usb_send(cmd); - if(cmd == '\n'){ - timgpio_transfer(buf, *len); - *len = 0; - lastidx = 0; - return; - } - } -} - -/** - * Send char array wrd thru USB - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/GPIO_TIM/user_proto.h b/GPIO_TIM/user_proto.h deleted file mode 100644 index 3835098..0000000 --- a/GPIO_TIM/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -void parse_incoming_buf(uint8_t *buf, int *len); - -#endif // __USER_PROTO_H__ diff --git a/GPS+ultrasonic/GPS.c b/GPS+ultrasonic/GPS.c deleted file mode 100644 index 1aab8d4..0000000 --- a/GPS+ultrasonic/GPS.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - * GPS.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "GPS.h" -#include "uart.h" - -#define GPS_endline() do{GPS_send_string((uint8_t*)"\r\n");}while(0) -#define U(arg) ((uint8_t*)arg) - -gps_status GPS_status = GPS_WAIT; - -void GPS_send_string(uint8_t *str){ - while(*str) - fill_uart_buff(USART2, *str++); -} - -int strncmp(const uint8_t *one, const uint8_t *two, int n){ - int diff = 0; - do{ - diff = (int)(*one++) - (int)(*two++); - }while(--n && diff == 0); - return diff; -} - -uint8_t *ustrchr(uint8_t *str, uint8_t symbol){ -// uint8_t *ptr = str; - do{ - if(*str == symbol) return str; - }while(*(++str)); - return NULL; -} - -uint8_t hex(uint8_t n){ - return ((n < 10) ? (n+'0') : (n+'A'-10)); -} - -/** - * Check checksum - */ -int checksum_true(uint8_t *buf){ - uint8_t *eol; - uint8_t checksum = 0, cs[3]; - if(*buf != '$' || !(eol = ustrchr(buf, '*'))){ - DBG("Wrong data: "); - DBG(buf); - DBG("\n"); - return 0; - } - while(++buf != eol) - checksum ^= *buf; - ++buf; - cs[0] = hex(checksum >> 4); - cs[1] = hex(checksum & 0x0f); - if(buf[0] == cs[0] && buf[1] == cs[1]) - return 1; -#ifdef EBUG - cs[2] = 0; - P("CHS, get "); - P(buf); - P(" need "); - P(cs); - usb_send('\n'); -#endif - return 0; -} - -void send_chksum(uint8_t chs){ - fill_uart_buff(USART2, hex(chs >> 4)); - fill_uart_buff(USART2, hex(chs & 0x0f)); -} -/** - * Calculate checksum & write message to port - * @param buf - command to write (with leading $ and trailing *) - * return 0 if fails - */ -void write_with_checksum(uint8_t *buf){ - uint8_t checksum = 0; - GPS_send_string(buf); - ++buf; // skip leaders - do{ - checksum ^= *buf++; - }while(*buf && *buf != '*'); - send_chksum(checksum); - GPS_endline(); -} - -/** - * set rate for given NMEA field - * @param field - name of NMEA field - * @param rate - rate in seconds (0 disables field) - * @return -1 if fails, rate if OK - */ -void block_field(const uint8_t *field){ - uint8_t buf[22]; - memcpy(buf, U("$PUBX,40,"), 9); - memcpy(buf+9, field, 3); - memcpy(buf+12, U(",0,0,0,0*"), 9); - buf[21] = 0; - write_with_checksum(buf); -} - - -/** - * Send starting sequences (get only RMC messages) - */ -void GPS_send_start_seq(){ - const uint8_t *GPmsgs[5] = {U("GSV"), U("GSA"), U("GGA"), U("GLL"), U("VTG")}; - int i; - for(i = 0; i < 5; ++i) - block_field(GPmsgs[i]); -} -/* -uint8_t *nextpos(uint8_t **buf, int pos){ - int i; - if(pos < 1) pos = 1; - for(i = 0; i < pos; ++i){ - *buf = ustrchr(*buf, ','); - if(!*buf) break; - ++(*buf); - } - return *buf; -} -#define NEXT() do{if(!nextpos(&buf, 1)) goto ret;}while(0) -#define SKIP(NPOS) do{if(!nextpos(&buf, NPOS)) goto ret;}while(0) -*/ -/** - * Parse answer from GPS module - * - * Recommended minimum specific GPS/Transit data - * $GPRMC,hhmmss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs - * 1 = UTC of position fix - * 2 = Data status (V=navigation receiver warning) - * 3 = Latitude of fix - * 4 = N or S - * 5 = Longitude of fix - * 6 = E or W - * 7 = Speed over ground in knots - * 8 = Cource over ground in degrees - * 9 = UT date - * 10 = Magnetic variation degrees (Easterly var. subtracts from true course) - * 11 = E or W - * 12 = Mode: N(bad), E(approx), A(auto), D(diff) - * 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B - */ -void GPS_parse_answer(uint8_t *buf){ - uint8_t *ptr; - if(strncmp(buf+3, U("RMC"), 3)){ // not RMC message - GPS_send_start_seq(); - return; - } - if(!checksum_true(buf)){ - DBG("Wrong chs\n"); - return; // wrong checksum - } - buf += 7; // skip header - if(*buf == ','){ // time unknown - GPS_status = GPS_WAIT; - return; - } - //P("time: "); - ptr = ustrchr(buf, ','); - *ptr++ = 0; - //P(buf); - if(*ptr == 'A'){ - GPS_status = GPS_VALID; - set_time(buf); - }else - GPS_status = GPS_NOT_VALID; -// buf = ustrchr(ptr, ','); -// P(" "); -// P("\n"); -} - -/* - -void rmc(uint8_t *buf){ - //DBG("rmc: %s\n", buf); - int H, M, LO, LA, d, m, y, getdate = 0; - double S, longitude, lattitude, speed, track, mag; - char varn = 'V', north = '0', east = '0', mageast = '0', mode = 'N'; - sscanf((char*)buf, "%2d%2d%lf", &H, &M, &S); - NEXT(); - if(*buf != ',') varn = *buf; - if(varn != 'A') - PRINT("(data could be wrong)"); - else{ - PRINT("(data valid)"); - if(GP->date) getdate = 1; // as only we have valid data we show it to user - } - PRINT(" time: %02d:%02d:%05.2f", H, M, S); - PRINT(" timediff: %g", timediff(H, M, S)); - NEXT(); - sscanf((char*)buf, "%2d%lf", &LA, &lattitude); - NEXT(); - if(*buf != ','){ - north = *buf; - lattitude = (double)LA + lattitude / 60.; - if(north == 'S') lattitude = -lattitude; - PRINT(" latt: %g", lattitude); - Latt_mean += lattitude; - Latt_sq += lattitude*lattitude; - ++Latt_N; - } - NEXT(); - sscanf((char*)buf, "%3d%lf", &LO, &longitude); - NEXT(); - if(*buf != ','){ - east = *buf; - longitude = (double)LO + longitude / 60.; - if(east == 'W') longitude = -longitude; - PRINT(" long: %g", longitude); - Long_mean += longitude; - Long_sq += longitude*longitude; - ++Long_N; - } - NEXT(); - if(*buf != ','){ - sscanf((char*)buf, "%lf", &speed); - PRINT(" speed: %gknots", speed); - } - NEXT(); - if(*buf != ','){ - sscanf((char*)buf, "%lf", &track); - PRINT(" track: %gdeg,True", track); - } - NEXT(); - if(sscanf((char*)buf, "%2d%2d%2d", &d, &m, &y) == 3) - PRINT(" date(dd/mm/yy): %02d/%02d/%02d", d, m, y); - if(getdate) show_date(H,M,S,d,m,y); // show date & exit - NEXT(); - sscanf((char*)buf, "%lf,%c", &mag, &mageast); - if(mageast == 'E' || mageast == 'W'){ - if(mageast == 'W') mag = -mag; - PRINT(" magnetic var: %g", mag); - } - SKIP(2); - if(*buf != ','){ - mode = *buf; - PRINT(" mode: %c", mode); - } -ret: - PRINT("\n"); -} -*/ diff --git a/GPS+ultrasonic/GPS.h b/GPS+ultrasonic/GPS.h deleted file mode 100644 index d400864..0000000 --- a/GPS+ultrasonic/GPS.h +++ /dev/null @@ -1,37 +0,0 @@ -/* - * GPS.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __GPS_H__ -#define __GPS_H__ - -typedef enum{ - GPS_WAIT // wait for satellites - ,GPS_NOT_VALID // time known, but not valid - ,GPS_VALID -} gps_status; - -extern gps_status GPS_status; - -void GPS_parse_answer(uint8_t *string); -void GPS_send_start_seq(); - -#endif // __GPS_H__ diff --git a/GPS+ultrasonic/Makefile b/GPS+ultrasonic/Makefile deleted file mode 100644 index e446d34..0000000 --- a/GPS+ultrasonic/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = timelapse -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/GPS+ultrasonic/README b/GPS+ultrasonic/README deleted file mode 100644 index 76acd02..0000000 --- a/GPS+ultrasonic/README +++ /dev/null @@ -1,8 +0,0 @@ -GPS-based timelapse tool -Connect up to four sensors (ultrasonic, infrared, laser and simple switch) -and get precision (milliseconds) time of their signals - -written for chinese devboard based on STM32F103RBT6 - -Press H for help - diff --git a/GPS+ultrasonic/adc.c b/GPS+ultrasonic/adc.c deleted file mode 100644 index e965b54..0000000 --- a/GPS+ultrasonic/adc.c +++ /dev/null @@ -1,140 +0,0 @@ -/* - * adc.c - functions for Sharp 2Y0A02 distance meter & photosensor - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "adc.h" -#include "main.h" - -uint16_t ADC_value[ADC_CHANNEL_NUMBER]; // Values of ADC -uint16_t ADC_trig_val[ADC_CHANNEL_NUMBER]; // -//- at trigger time - -void init_adc_sensor(){ - // we will use ADC1 channel 0 for IR sensor & ADC1 channel 1 for laser's photoresistor - uint8_t adc_channel_array[ADC_CHANNEL_NUMBER] = {0,1}; - // Make sure the ADC doesn't run during config - adc_off(ADC1); - // enable ADC & PA0/PA1 clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN | RCC_APB2ENR_IOPAEN); - rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4); - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0 | GPIO1); - rcc_periph_clock_enable(RCC_DMA1); // enable DMA for ADC values storing - // Configure ADC as continuous scan mode with DMA - ADC1_CR1 = ADC_CR1_SCAN; // enable scan mode - // set sample time on channels 1&2: 239.5 cycles for better results - ADC1_SMPR2 = 0x3f; - dma_channel_reset(DMA1, DMA_CHANNEL1); - DMA1_CPAR1 = (uint32_t) &(ADC_DR(ADC1)); - DMA1_CMAR1 = (uint32_t) ADC_value; - DMA1_CNDTR1 = ADC_CHANNEL_NUMBER; - DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT - | DMA_CCR_CIRC | DMA_CCR_PL_HIGH | DMA_CCR_EN; - // continuous conv, enable ADC & DMA - ADC1_CR2 = ADC_CR2_CONT | ADC_CR2_ADON | ADC_CR2_DMA; - // set channels - adc_set_regular_sequence(ADC1, ADC_CHANNEL_NUMBER, adc_channel_array); - // reset calibration registers & start calibration - ADC1_CR2 |= ADC_CR2_RSTCAL; - while(ADC1_CR2 & ADC_CR2_RSTCAL); // wait for registers reset - ADC1_CR2 |= ADC_CR2_CAL; - while(ADC1_CR2 & ADC_CR2_CAL); // wait for calibration ends - // set threshold limits -// ADC1_HTR = ADC_WDG_HIGH; -// ADC1_LTR = ADC_WDG_LOW; - // enable analog watchdog on single regular channel 0 & enable interrupt - //ADC1_CR1 = ADC_CR1_AWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDIE; - // enable analog watchdog on all regular channels & enable interrupt -// ADC1_CR1 |= ADC_CR1_AWDEN | ADC_CR1_AWDIE; - nvic_enable_irq(NVIC_ADC1_2_IRQ); - ADC1_CR2 |= ADC_CR2_SWSTART; - // turn on ADC - to do it we need set ADC_CR2_ADON again! - ADC1_CR2 |= ADC_CR2_ADON; -} - -adwd_stat adc_status[ADC_CHANNEL_NUMBER] = {ADWD_MID, ADWD_MID}; - -/** - * watchdog works on both channels, so we need to save status of WD events - * to prevent repeated events on constant signal level - * -void adc1_2_isr(){ - int i; - if(ADC1_SR & ADC_SR_AWD){ // analog watchdog event - for(i = 0; i < ADC_CHANNEL_NUMBER; ++i){ - uint16_t val = ADC_value[i]; - adwd_stat st = adc_status[i]; - // if(adc_ms[i] == DIDNT_TRIGGERED){ - if(val > ADC_WDG_HIGH){ // watchdog event on high level - if(st != ADWD_HI){ - adc_ms[i] = Timer; - memcpy(&adc_time, ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_HI; - ADC_trig_val[i] = val; - } - }else if(val < ADC_WDG_LOW){ // watchdog event on low level - if(st != ADWD_LOW){ - adc_ms[i] = Timer; - memcpy(&adc_time, ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_LOW; - ADC_trig_val[i] = val; - } - }else if(val > ADC_WDG_LOW+ADC_WDG_THRES && val < ADC_WDG_HIGH-ADC_WDG_THRES){ - adc_status[i] = ADWD_MID; - if(adc_ms[i] == Timer) // remove noice - adc_ms[i] = DIDNT_TRIGGERED; - } - // } - } - } - ADC1_SR = 0; -} -*/ - -// levels for thresholding -const uint16_t ADC_lowlevel[2] = {900, 2700}; // signal if ADC value < lowlevel -const uint16_t ADC_highlevel[2] = {2200, 5000}; // signal if ADC value > highlevel -const uint16_t ADC_midlevel[2] = {1400, 3000}; // when transit through midlevel set status as ADWD_MID - -void poll_ADC(){ - int i; - for(i = 0; i < ADC_CHANNEL_NUMBER; ++i){ - uint16_t val = ADC_value[i]; - adwd_stat st = adc_status[i]; - if(val > ADC_highlevel[i]){ // watchdog event on high level - if(st != ADWD_HI){ - adc_ms[i] = Timer; - memcpy(&adc_time[i], ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_HI; - ADC_trig_val[i] = val; - } - }else if(val < ADC_lowlevel[i]){ // watchdog event on low level - if(st != ADWD_LOW){ - adc_ms[i] = Timer; - memcpy(&adc_time[i], ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_LOW; - ADC_trig_val[i] = val; - } - }else if((st == ADWD_HI && val < ADC_midlevel[i]) || - (st == ADWD_LOW && val > ADC_midlevel[i])){ - adc_status[i] = ADWD_MID; - if(adc_ms[i] == Timer) // remove noice - adc_ms[i] = DIDNT_TRIGGERED; - } - } -} diff --git a/GPS+ultrasonic/adc.h b/GPS+ultrasonic/adc.h deleted file mode 100644 index fffedb0..0000000 --- a/GPS+ultrasonic/adc.h +++ /dev/null @@ -1,52 +0,0 @@ -/* - * adc.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SHARP_H__ -#define __SHARP_H__ - -#include - -extern uint16_t ADC_value[]; -extern uint16_t ADC_trig_val[]; - -typedef enum{ - ADWD_LOW, // watchdog at low-level - ADWD_MID, // normal state - ADWD_HI // watchdog at high-level -} adwd_stat; - -extern adwd_stat adc_status[]; - - -#define ADC_CHANNEL_NUMBER (2) - -// something near -#define ADC_WDG_HIGH ((uint16_t)1500) -// nothing in front of sensor -#define ADC_WDG_LOW ((uint16_t)700) -// threshold above levels -#define ADC_WDG_THRES ((uint16_t)200) - -void init_adc_sensor(); -void poll_ADC(); - -#endif // __SHARP_H__ diff --git a/GPS+ultrasonic/cdcacm.c b/GPS+ultrasonic/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/GPS+ultrasonic/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/GPS+ultrasonic/cdcacm.h b/GPS+ultrasonic/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/GPS+ultrasonic/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/GPS+ultrasonic/hardware_ini.c b/GPS+ultrasonic/hardware_ini.c deleted file mode 100644 index a43dceb..0000000 --- a/GPS+ultrasonic/hardware_ini.c +++ /dev/null @@ -1,121 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - /* - * Setup EXTI on PA4 (PPS input from GPS) - pull down - * EXTI on PA5 - also pull down (trigger for time measurement) - */ - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO4 | GPIO5); - //AFIO_EXTICR2 = 0; - exti_enable_request(EXTI4 | EXTI5); - // trigger on rising edge - exti_set_trigger(EXTI4 | EXTI5, EXTI_TRIGGER_RISING); - nvic_enable_irq(NVIC_EXTI4_IRQ); - nvic_enable_irq(NVIC_EXTI9_5_IRQ); -/* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN);*/ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - STK_RVR = STK_RVR_DEFAULT_VAL; // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -/** - * PA5 interrupt - print time at button/switch trigger - */ -void exti9_5_isr(){ - if(EXTI_PR & EXTI5){ - if(trigger_ms == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms = Timer; - memcpy(&trigger_time, ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI5; - } -} - -/* -// check buttons S2/S3 -void check_btns(){ - static uint8_t oldstate[2] = {1,1}; // old buttons state - uint8_t newstate[2], i; - static uint32_t Old_timer[2] = {0,0}; - newstate[0] = gpio_get(BTNS_PORT, BTN_S2_PIN) ? 1 : 0; - newstate[1] = gpio_get(BTNS_PORT, BTN_S3_PIN) ? 1 : 0; - for(i = 0; i < 2; i++){ - uint8_t new = newstate[i]; - // pause for 60ms - uint32_t O = Old_timer[i]; - if(O){ - if(Timer - O > 60 || O > Timer){ - P("Button S"); - usb_send('2' + i); - if(new) P("released"); - else P("pressed"); - newline(); - oldstate[i] = new; - Old_timer[i] = 0; - } - } - else if(new != oldstate[i]){ - Old_timer[i] = Timer; - } - } -} -*/ diff --git a/GPS+ultrasonic/hardware_ini.h b/GPS+ultrasonic/hardware_ini.h deleted file mode 100644 index ff0311f..0000000 --- a/GPS+ultrasonic/hardware_ini.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * Buttons on devboard - */ -#define BTNS_PORT GPIOC -// PCO -- S2 -#define BTN_S2_PIN GPIO0 -// PC1 -- S3 -#define BTN_S3_PIN GPIO1 - -/* - * LEDS: PB9 for D1, PB8 for D2 - */ -#define LEDS_PORT GPIOB -#define LED_D1_PIN GPIO9 -#define LED_D2_PIN GPIO8 - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -void check_btns(); - -#endif // __HARDWARE_INI_H__ diff --git a/GPS+ultrasonic/ld/devices.data b/GPS+ultrasonic/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/GPS+ultrasonic/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/GPS+ultrasonic/ld/stm32f103x4.ld b/GPS+ultrasonic/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/GPS+ultrasonic/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103x6.ld b/GPS+ultrasonic/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/GPS+ultrasonic/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103x8.ld b/GPS+ultrasonic/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/GPS+ultrasonic/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xB.ld b/GPS+ultrasonic/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/GPS+ultrasonic/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xC.ld b/GPS+ultrasonic/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/GPS+ultrasonic/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xD.ld b/GPS+ultrasonic/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/GPS+ultrasonic/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xE.ld b/GPS+ultrasonic/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/GPS+ultrasonic/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xF.ld b/GPS+ultrasonic/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/GPS+ultrasonic/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/ld/stm32f103xG.ld b/GPS+ultrasonic/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/GPS+ultrasonic/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS+ultrasonic/main.c b/GPS+ultrasonic/main.c deleted file mode 100644 index a45ced8..0000000 --- a/GPS+ultrasonic/main.c +++ /dev/null @@ -1,271 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "uart.h" -#include "GPS.h" -#include "ultrasonic.h" -#include "adc.h" - -volatile uint32_t Timer = 0; // milliseconds -volatile uint32_t msctr = 0; // global milliseconds for different purposes -usbd_device *usbd_dev; -volatile int32_t systick_val = 0; -volatile int32_t timer_val = 0; -volatile int clear_ST_on_connect = 1; - -volatile int need_sync = 1; - -volatile uint32_t last_corr_time = 0; // time of last PPS correction (seconds from midnight) - -// STK_CVR values for all milliseconds (RVR0) and last millisecond (RVR1) -volatile uint32_t RVR0 = STK_RVR_DEFAULT_VAL, RVR1 = STK_RVR_DEFAULT_VAL; - -curtime current_time = {25,61,61}; - -curtime trigger_time = {25, 61, 61}; -curtime adc_time[ADC_CHANNEL_NUMBER] = {{25, 61, 61}, {25, 61, 61}}; -curtime ultrasonic_time = {25, 61, 61}; -uint32_t trigger_ms = DIDNT_TRIGGERED, adc_ms[ADC_CHANNEL_NUMBER] = {DIDNT_TRIGGERED, DIDNT_TRIGGERED}, - ultrasonic_ms = DIDNT_TRIGGERED; - -void time_increment(){ - Timer = 0; - if(current_time.H == 25) return; // Time not initialized - if(++current_time.S == 60){ - current_time.S = 0; - if(++current_time.M == 60){ - current_time.M = 0; - if(++current_time.H == 24) - current_time.H = 0; - } - } -} - -int main(){ - uint8_t *string; - int i; - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - UART_init(USART2); // init GPS UART - - tim2_init(); - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - GPS_send_start_seq(); - init_adc_sensor(); - - uint32_t trigrtm = 0, adctm[2] = {0, 0}, ultrasonictm = 0; - while(1){ - usbd_poll(usbd_dev); - poll_ultrasonic(); - poll_ADC(); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - if((string = check_UART2())){ - // P(string); - GPS_parse_answer(string); - } - if(systick_val > 1000){ - P("Systick differs by "); - print_int(systick_val); - systick_val = 0; - P(", timer value: "); - print_int(timer_val); - P(", RVR0 = "); - print_int(RVR0); - P(", RVR1 = "); - print_int(RVR1); - P("\n"); - print_curtime(); - } - if(trigger_ms != DIDNT_TRIGGERED && trigger_ms != Timer){ - if(msctr - trigrtm > 500 || trigrtm > msctr){ - trigrtm = msctr; - P("Trigger time: "); - print_time(&trigger_time, trigger_ms); - } - trigger_ms = DIDNT_TRIGGERED; - } - for(i = 0; i < ADC_CHANNEL_NUMBER; ++i){ - if(adc_ms[i] != DIDNT_TRIGGERED && adc_ms[i] != Timer){ - if(msctr - adctm[i] > 500 || adctm[i] > msctr){ - /*int16_t diff = ADC_trig_val[i] - ADC_value[i]; - if(diff < 0) diff = -diff; - if(diff < ADC_WDG_THRES/2){ // omit noice - */ - adctm[i] = msctr; - P("ADC"); - usb_send('0'+i); - if(adc_status[i] == ADWD_HI) P("hi"); - else if(adc_status[i] == ADWD_LOW) P("lo"); - P(": value = "); - print_int(ADC_trig_val[i]); - P(" (now: "); - print_int(ADC_value[i]); - P("), time = "); - print_time(&adc_time[i], adc_ms[i]); - //} - } - adc_ms[i] = DIDNT_TRIGGERED; - } - } - if(ultrasonic_ms != DIDNT_TRIGGERED && ultrasonic_ms != Timer){ - if(msctr - ultrasonictm > 500 || ultrasonictm > msctr){ - ultrasonictm = msctr; - P("Ultrasonic time: "); - print_time(&ultrasonic_time, ultrasonic_ms); - } - ultrasonic_ms = DIDNT_TRIGGERED; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - ++Timer; - ++msctr; - if(Timer == 999){ - STK_RVR = RVR1; - }else if(Timer == 1000){ - STK_RVR = RVR0; - time_increment(); - } - usb_send_buffer(); -} -// STK_CVR - current systick val -// STK_RVR - ticks till interrupt - 1 - -// PA4 interrupt - PPS signal -void exti4_isr(){ - uint32_t t = 0, ticks; - static uint32_t ticksavr = 0, N = 0; - if(EXTI_PR & EXTI4){ - // correct - systick_val = STK_CVR; - STK_CVR = RVR0; - timer_val = Timer; - Timer = 0; - systick_val = STK_RVR + 1 - systick_val; // Systick counts down! - if(timer_val < 10) timer_val += 1000; // our closks go faster than real - else if(timer_val < 990){ // something wrong - RVR0 = RVR1 = STK_RVR_DEFAULT_VAL; - STK_RVR = RVR0; - need_sync = 1; - goto theend; - }else - time_increment(); // ms counter less than 1000 - we need to increment time - t = current_time.H * 3600 + current_time.M * 60 + current_time.S; - if(clear_ST_on_connect){ - clear_ST_on_connect = 0; - }else{ - // || (last_corr_time == 86399 && t == 0) - if(t - last_corr_time == 1){ // PPS interval == 1s - ticks = systick_val + (timer_val-1)*(RVR0 + 1) + RVR1 + 1; - ++N; - ticksavr += ticks; - if(N > 20){ - ticks = ticksavr / N; - RVR0 = ticks / 1000 - 1; // main RVR value - STK_RVR = RVR0; - RVR1 = RVR0 + ticks % 1000; // last millisecond RVR value (with fine correction) - N = 0; - ticksavr = 0; - need_sync = 0; - } - }else{ - N = 0; - ticksavr = 0; - } - } - theend: - last_corr_time = t; - EXTI_PR = EXTI4; - } -} - -// pause function, delay in ms -void Delay(uint16_t time){ - uint32_t waitto = msctr + time; - while(msctr != waitto); -} - -/** - * set current time by buffer hhmmss - */ -void set_time(uint8_t *buf){ - inline uint8_t atou(uint8_t *b){ - return (b[0]-'0')*10 + b[1]-'0'; - } - uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS; - if(H > 23) H -= 24; - current_time.H = H; - current_time.M = atou(&buf[2]); - current_time.S = atou(&buf[4]); -} - -/** - * print time: Tm - time structure, T - milliseconds - */ -void print_time(curtime *Tm, uint32_t T){ - int S = Tm->S, M = Tm->M, H = Tm->H; - if(H < 10) usb_send('0'); - print_int(H); usb_send(':'); - if(M < 10) usb_send('0'); - print_int(M); usb_send(':'); - if(S < 10) usb_send('0'); - print_int(S); usb_send('.'); - if(T < 100) usb_send('0'); - if(T < 10) usb_send('0'); - print_int(T); - if(GPS_status == GPS_NOT_VALID) P(" (not valid)"); - if(need_sync) P(" need synchronisation"); - newline(); -} - -void print_curtime(){ - uint32_t T = Timer; - if(current_time.H < 24 && GPS_status != GPS_WAIT){ - P("Current time: "); - print_time(¤t_time, T); - }else - P("Waiting for satellites\n"); -} diff --git a/GPS+ultrasonic/main.h b/GPS+ultrasonic/main.h deleted file mode 100644 index 0ffb0b7..0000000 --- a/GPS+ultrasonic/main.h +++ /dev/null @@ -1,77 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "sync.h" // mutexes -#include "user_proto.h" - -extern void *memcpy(void *dest, const void *src, int n); - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -#define STK_RVR_DEFAULT_VAL (8999) -#define TIMEZONE_GMT_PLUS (3) - -#define DIDNT_TRIGGERED (2000) - -typedef struct{ - uint8_t H; - uint8_t M; - uint8_t S; -} curtime; - -extern curtime current_time; -extern volatile uint32_t Timer; // global timer (milliseconds) -extern volatile int clear_ST_on_connect; // flag for clearing Systick counter on next PPS - -extern curtime trigger_time, adc_time[], ultrasonic_time; -extern uint32_t trigger_ms, adc_ms[], ultrasonic_ms; - -extern volatile int need_sync; - -void Delay(uint16_t time); -void set_time(uint8_t *buf); - -void print_time(curtime *T, uint32_t m); -void print_curtime(); - -#endif // __MAIN_H__ - diff --git a/GPS+ultrasonic/sync.c b/GPS+ultrasonic/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/GPS+ultrasonic/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/GPS+ultrasonic/sync.h b/GPS+ultrasonic/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/GPS+ultrasonic/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/GPS+ultrasonic/timelapse.bin b/GPS+ultrasonic/timelapse.bin deleted file mode 100755 index f653929..0000000 Binary files a/GPS+ultrasonic/timelapse.bin and /dev/null differ diff --git a/GPS+ultrasonic/uart.c b/GPS+ultrasonic/uart.c deleted file mode 100644 index 707e428..0000000 --- a/GPS+ultrasonic/uart.c +++ /dev/null @@ -1,262 +0,0 @@ -/* - * uart.c - functions to work with UART - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "uart.h" -#include "cdcacm.h" -#include "hardware_ini.h" - -// Buffers for Tx -static UART_buff TX_buffer[2]; // Tx buffers for all three ports -static UART_buff RX_buffer[2]; // Rx buffers for all three ports - -void fill_uart_RXbuff(uint32_t UART, uint8_t byte); - -/** - * Set UART speed - * @param lc - UART parameters or NULL for value from cdcacm.c (started - B115200,8,N,1) - */ -void UART_setspeed(uint32_t UART){ - usart_set_baudrate(UART, 9600); - usart_set_databits(UART, 8); - usart_set_stopbits(UART, USART_STOPBITS_1); - usart_set_parity(UART, USART_PARITY_NONE); - usart_set_flow_control(UART, USART_FLOWCONTROL_NONE); - usart_set_mode(UART, USART_MODE_TX_RX); -} - -/** - * Setup UART - */ -void UART_init(uint32_t UART){ - uint32_t irq, rcc, rccgpio, gpioport, gpiopin; - switch(UART){ - case USART2: // GPS UART - irq = NVIC_USART2_IRQ; // interrupt for given USART - rcc = RCC_USART2; // RCC timing of USART - rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output) - TX_buffer[1].end = 0; // reset counters - TX_buffer[1].start = 0; - RX_buffer[1].end = 0; - RX_buffer[1].start = 0; - // output pin setup - gpioport = GPIO_BANK_USART2_TX; - gpiopin = GPIO_USART2_TX; - break; - case USART1: - default: - irq = NVIC_USART1_IRQ; - rcc = RCC_USART1; - rccgpio = RCC_GPIOA; - TX_buffer[0].end = 0; - TX_buffer[0].start = 0; - RX_buffer[0].end = 0; - RX_buffer[0].start = 0; - gpioport = GPIO_BANK_USART1_TX; - gpiopin = GPIO_USART1_TX; - } - // enable clocking - rcc_periph_clock_enable(RCC_AFIO); // alternate functions - rcc_periph_clock_enable(rcc); // USART - rcc_periph_clock_enable(rccgpio); // GPIO pins - // enable output pin - gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin); - // enable IRQ - nvic_enable_irq(irq); - UART_setspeed(UART); - // Enable UART receive interrupt - USART_CR1(UART) |= USART_CR1_RXNEIE; - // Enable UART - usart_enable(UART); -} - -/* - * UART interrupts - */ -// common -void UART_isr(uint32_t UART){ - uint8_t bufidx = 0, data; - UART_buff *curbuff; - // Check if we were called because of RXNE - if(USART_SR(UART) & USART_SR_RXNE){ - // parse incoming byte - data = usart_recv(UART); - fill_uart_RXbuff(UART, data); - } - // Check if we were called because of TXE -> send next byte in buffer - if((USART_CR1(UART) & USART_CR1_TXEIE) && (USART_SR(UART) & USART_SR_TXE)){ - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - if(bufidx != curbuff->end){ // there's data in buffer - // Put data into the transmit register - usart_send(UART, curbuff->buf[bufidx]); - if(++(curbuff->start) == UART_BUF_DATA_SIZE){ // reload start - curbuff->start = 0; - } - }else{ // Disable the TXE interrupt, it's no longer needed - USART_CR1(UART) &= ~USART_CR1_TXEIE; - // empty indexes - curbuff->start = 0; - curbuff->end = 0; - } - } -} -// particular interrupt handlers -void usart1_isr(){ - UART_isr(USART1); -} -void usart2_isr(){ - UART_isr(USART2); -} - -// put byte into Tx buffer -void fill_uart_buff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx = 0, endidx; - if(!(USART_CR1(UART) & USART_CR1_UE)) return; // UART disabled - USART_CR1(UART) &= ~USART_CR1_TXEIE; // disable TX interrupt while buffer filling - while ((USART_SR(UART) & USART_SR_TXE) == 0); // wait until last byte send - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - endidx = curbuff->end; // end of data - curbuff->buf[endidx++] = byte; // put byte into buffer - // now check indexes - if(endidx != bufidx && endidx != UART_BUF_DATA_SIZE){ // all OK - there's enough place for data - (curbuff->end)++; // just increment index in buffer - }else{ // dangerous situation: possible overflow - if(endidx == UART_BUF_DATA_SIZE){ // end of buffer - if(bufidx != 0){ // no overflow - curbuff->end = 0; - goto end_of_fn; - } - } - // overflow: purge all data - bufidx = curbuff->start; // refresh data index - for(endidx = bufidx; endidx < UART_BUF_DATA_SIZE; endidx++) // first data porion - usart_send(UART, curbuff->buf[endidx]); - for(endidx = 0; endidx < bufidx; endidx++) // rest of data - usart_send(UART, curbuff->buf[endidx]); - curbuff->start = 0; - curbuff->end = 0; - return; - } - end_of_fn: - // enable interrupts to send data from buffer - USART_CR1(UART) |= USART_CR1_TXEIE; -} - -/** - * send data over UART - one function for each uart - * @param byte - one byte to put in UART queue - */ -void uart1_send(uint8_t byte){ - fill_uart_buff(USART1, byte); -} -void uart2_send(uint8_t byte){ - fill_uart_buff(USART2, byte); -} -/* -UART_buff *get_uart_buffer(uint32_t UART){ - switch(UART){ - case USART1: - return &RX_buffer[0]; - break; - case USART2: - return &RX_buffer[1]; - break; - default: // error - return - return NULL; - } - return NULL; -}*/ - - -/** - * Check whether UART2 have a full text line - * @return string with data if data ready or NULL - */ -uint8_t *check_UART2(){ - static int oldlen = 0; - static uint8_t buf[UART_BUF_DATA_SIZE+1]; - UART_buff *curbuff = &RX_buffer[1]; - uint8_t datalen = curbuff->end; // length of data in buffer - here we use param "end" - if(!datalen) return NULL; // buffer is empty - if(oldlen != datalen){ - if(curbuff->buf[curbuff->end-1] != '\n'){ // string not full - oldlen = datalen; - return NULL; - }else{ // full string - copy it to buffer & clear indexes - memcpy(buf, curbuff->buf, datalen); - buf[datalen] = 0; - oldlen = curbuff->end = 0; - return buf; - } - } - return NULL; -} - -/** - * Fill data in RX buffer to prepare it for further work - * we don't use "start" parameter here, it's 0 always - * @param UART - device to fill buffer - * @param byte - data byte - */ -void fill_uart_RXbuff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx; - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &RX_buffer[bufidx]; - if(curbuff->end == UART_BUF_DATA_SIZE){ // end of buffer - forget about data - curbuff->end = 0; - return; - } - curbuff->buf[curbuff->end++] = byte; // put byte into buffer -} diff --git a/GPS+ultrasonic/uart.h b/GPS+ultrasonic/uart.h deleted file mode 100644 index 85715ca..0000000 --- a/GPS+ultrasonic/uart.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * uart.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __UART_H__ -#define __UART_H__ - -// Size of buffers -#define UART_BUF_DATA_SIZE 128 - -typedef struct { - uint8_t buf[UART_BUF_DATA_SIZE]; - uint8_t start; // index from where to start reading - uint8_t end; // index from where to start writing -} UART_buff; - -void UART_init(uint32_t UART); -void UART_setspeed(uint32_t UART); - -void fill_uart_buff(uint32_t UART, uint8_t byte); -void uart1_send(uint8_t byte); -void uart2_send(uint8_t byte); - -uint8_t *check_UART2(); - -UART_buff *get_uart_buffer(uint32_t UART); - -#endif // __UART_H__ diff --git a/GPS+ultrasonic/ultrasonic.c b/GPS+ultrasonic/ultrasonic.c deleted file mode 100644 index b6a6642..0000000 --- a/GPS+ultrasonic/ultrasonic.c +++ /dev/null @@ -1,199 +0,0 @@ -/* - * ultrasonic.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include -#include -#include -#include - -#include "ultrasonic.h" -#include "user_proto.h" -#include "main.h" - -static usmode US_mode = US_MODE_OFF; -static int overcapture = 0; - -#ifndef TIM_CCMR2_CC3S_IN_TI4 -#define TIM_CCMR2_CC3S_IN_TI4 (2) -#endif -#ifndef TIM_CCMR2_CC4S_IN_TI4 -#define TIM_CCMR2_CC4S_IN_TI4 (1 << 8) -#endif -/** - * Init timer 2 (&remap channels 3&4 to five-tolerant ports) - */ -void tim2_init(){ - // Turn off JTAG & SWD, remap TIM2_CH3/TIM2_CH4 to PB10/PB11 (five tolerant) - // don't forget about AFIO clock & PB clock! - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP2); - // setup PB10 & PB11 - // PB10 - Trig output - push/pull - gpio_set_mode(GPIO_BANK_TIM2_PR2_CH3, GPIO_MODE_OUTPUT_10_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_PR2_CH3); -// gpio_set_mode(GPIO_BANK_TIM2_CH3, GPIO_MODE_OUTPUT_10_MHZ, -// GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_CH3); - // PB11 - Echo input - floating -// gpio_set_mode(GPIO_BANK_TIM2_PR2_CH4, GPIO_MODE_INPUT, -// GPIO_CNF_INPUT_FLOAT, GPIO_TIM2_PR2_CH4); - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - // 36MHz of APB1 - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM2_PSC = 71; // prescaler is (div - 1) - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; -// DBG("Timer configured\n"); -} - -/** - * Send Trig signal - * return 0 if another measurement still in process - */ -void start_ultrasonic(){ - overcapture = 0; - TIM2_CR1 = 0; - //TIM2_CR1 = TIM_CR1_URS; // Turn off timer to reconfigure, dusable UEV by UG set - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_DIER = 0; - TIM2_SR = 0; // clear all flags - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; - // PWM_OUT for TIM2_CH3 - TIM2_CCMR2 = TIM_CCMR2_CC3S_OUT | TIM_CCMR2_OC3M_PWM1; - // start measurement, active is high - TIM2_CCER = TIM_CCER_CC3E; - // enable CC3 IRQ - TIM2_DIER = TIM_DIER_CC3IE; - nvic_enable_irq(NVIC_TIM2_IRQ); - US_mode = US_MODE_TRIG; - // start timer in one-pulse mode without update event - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN | TIM_CR1_UDIS; -} - -/** - * Start measurement: - * TIM2_CH3 will capture high level & TIM2_CH4 will capture low - * The timer configured to 65536us to detect signal lost - */ -inline void run_measrmnt(){ - US_mode = US_MODE_WAIT; - TIM2_CR1 = 0; // Turn off timer to reconfigure - TIM2_DIER = 0; - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - //DBG("triggered\n"); - TIM2_SR = 0; // clear all flags - TIM2_ARR = MAX_MSRMNT_LEN; - // TIM2_CH3 & TIM2_CH4 configured as inputs, TIM2_CH3 connected to CH4 - TIM2_CCMR2 = TIM_CCMR2_CC3S_IN_TI4 | TIM_CCMR2_CC4S_IN_TI4; - // start - TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; - // enable interrupts CH3, CH4 & update - TIM2_DIER = TIM_DIER_CC3IE | TIM_DIER_CC4IE | TIM_DIER_UIE; - // start timer in one-pulse mode - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN; -} - -void tim2_isr(){ - // No signal - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - TIM2_SR = 0; - overcapture = 1; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - US_mode = US_MODE_READY; - //DBG("overcaptured\n"); - } - // end of Trig pulse or start of measurements - if(TIM2_SR & TIM_SR_CC3IF){ // CCR ch3 interrupt - if(US_mode == US_MODE_TRIG){ // triggered - run measurement - run_measrmnt(); - }else if(US_mode == US_MODE_WAIT){ - US_mode = US_MODE_MEASUREMENT; - } - TIM2_SR &= ~TIM_SR_CC3IF; - } - if(TIM2_SR & TIM_SR_CC4IF){ - if(US_mode == US_MODE_MEASUREMENT){ - US_mode = US_MODE_READY; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - TIM2_CR1 = 0; // turn off timer - we don't need it more - } - TIM2_SR &= ~TIM_SR_CC3IF; - } -} - -/** - * Measure distance - * return 1 if measurements done - * set L to distance (in mm) or 0 in case of overcapture (no signal) - */ -int ultrasonic_get(uint32_t *L){ - uint32_t D; - if(US_mode != US_MODE_READY) - return 0; - US_mode = US_MODE_DONE; - if(!overcapture){ - D = ((uint32_t)(TIM2_CCR4 - TIM2_CCR3)) * 170; - *L = D / 1000; - }else *L = 0; - return 1; -} - -uint32_t last_us_val = 0; -void poll_ultrasonic(){ - uint32_t L; - if(US_mode == US_MODE_OFF){ - start_ultrasonic(); - return; - }//else if(ultrasonic_ms != DIDNT_TRIGGERED) return; - if(ultrasonic_get(&L)){ // measurements done, check event - if(!overcapture){ - if(!last_us_val){ - last_us_val = L; - }else{ - uint32_t diff = (last_us_val > L) ? last_us_val - L : L - last_us_val; - if(diff > MAX_LEN_DIFF){ - if(last_us_val > L){ // someone move in front of sensor - ultrasonic_ms = Timer; - memcpy(&ultrasonic_time, ¤t_time, sizeof(curtime)); - P("Pass! Was: "); - print_int(last_us_val); - P(", become: "); - print_int(L); - P("!!!\n"); - }else{ // free space - check for noices (signal should be at least 10ms) - diff = (ultrasonic_ms < Timer) ? Timer - ultrasonic_ms : ultrasonic_ms - Timer; - if(diff < ULTRASONIC_TIMEOUT) - ultrasonic_ms = DIDNT_TRIGGERED; - } - last_us_val = L; - } - } - } - start_ultrasonic(); - } -} diff --git a/GPS+ultrasonic/ultrasonic.h b/GPS+ultrasonic/ultrasonic.h deleted file mode 100644 index 39e17d3..0000000 --- a/GPS+ultrasonic/ultrasonic.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * ultrasonic.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __ULTRASONIC_H__ -#define __ULTRASONIC_H__ - -#include - -void tim2_init(); -int ultrasonic_get(uint32_t *L); -void poll_ultrasonic(); -extern uint32_t last_us_val; - -// Sensor mode -typedef enum{ - US_MODE_OFF // sensor is off - ,US_MODE_DONE // measurement done, ready for next - ,US_MODE_TRIG // sensor triggered - ,US_MODE_WAIT // wait for pulse - ,US_MODE_MEASUREMENT // measurement in process - ,US_MODE_READY // measurements done -} usmode; - -// trigger time: after trigger event ends, timer will be configured for capture - 20us -#define TRIG_T (200) -// trigger length - 10us -#define TRIG_L (10) -// max length of measurement (to detect signal absence) -#define MAX_MSRMNT_LEN (65535) -// max difference of measured len for pass detection -#define MAX_LEN_DIFF (300) -// minimal length of signal in ms -#define ULTRASONIC_TIMEOUT (10) -#endif // __ULTRASONIC_H__ diff --git a/GPS+ultrasonic/user_proto.c b/GPS+ultrasonic/user_proto.c deleted file mode 100644 index 2b322fa..0000000 --- a/GPS+ultrasonic/user_proto.c +++ /dev/null @@ -1,221 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "GPS.h" -#include "ultrasonic.h" -#include "adc.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("A\tshow ADC values\n"); - P("C\tclear SysTick on PPS\n"); - P("H\tshow this help\n"); - P("I\tInit ADC sensors\n"); - P("S\tSend GPS starting sequence\n"); - P("T\tshow current approx. time\n"); - P("U\tshow last measured distance by US\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0, j; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'A': - for(j=0; j '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/GPS+ultrasonic/user_proto.h b/GPS+ultrasonic/user_proto.h deleted file mode 100644 index 69bf771..0000000 --- a/GPS+ultrasonic/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/GPS/GPS.bin b/GPS/GPS.bin deleted file mode 100755 index 1a1b635..0000000 Binary files a/GPS/GPS.bin and /dev/null differ diff --git a/GPS/GPS.c b/GPS/GPS.c deleted file mode 100644 index 830a91a..0000000 --- a/GPS/GPS.c +++ /dev/null @@ -1,263 +0,0 @@ -/* - * GPS.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "GPS.h" -#include "uart.h" - -#define GPS_endline() do{GPS_send_string((uint8_t*)"\r\n");}while(0) -#define U(arg) ((uint8_t*)arg) - -gps_status GPS_status = GPS_WAIT; - -void GPS_send_string(uint8_t *str){ - while(*str) - fill_uart_buff(USART2, *str++); -} - -int strncmp(const uint8_t *one, const uint8_t *two, int n){ - int diff = 0; - do{ - diff = (int)(*one++) - (int)(*two++); - }while(--n && diff == 0); - return diff; -} - -uint8_t *ustrchr(uint8_t *str, uint8_t symbol){ -// uint8_t *ptr = str; - do{ - if(*str == symbol) return str; - }while(*(++str)); - return NULL; -} - -uint8_t hex(uint8_t n){ - return ((n < 10) ? (n+'0') : (n+'A'-10)); -} - -/** - * Check checksum - */ -int checksum_true(uint8_t *buf){ - uint8_t *eol; - uint8_t checksum = 0, cs[3]; - if(*buf != '$' || !(eol = ustrchr(buf, '*'))){ - DBG("Wrong data: "); - DBG(buf); - DBG("\n"); - return 0; - } - while(++buf != eol) - checksum ^= *buf; - ++buf; - cs[0] = hex(checksum >> 4); - cs[1] = hex(checksum & 0x0f); - if(buf[0] == cs[0] && buf[1] == cs[1]) - return 1; -#ifdef EBUG - cs[2] = 0; - P("CHS, get "); - P(buf); - P(" need "); - P(cs); - usb_send('\n'); -#endif - return 0; -} - -void send_chksum(uint8_t chs){ - fill_uart_buff(USART2, hex(chs >> 4)); - fill_uart_buff(USART2, hex(chs & 0x0f)); -} -/** - * Calculate checksum & write message to port - * @param buf - command to write (with leading $ and trailing *) - * return 0 if fails - */ -void write_with_checksum(uint8_t *buf){ - uint8_t checksum = 0; - GPS_send_string(buf); - ++buf; // skip leaders - do{ - checksum ^= *buf++; - }while(*buf && *buf != '*'); - send_chksum(checksum); - GPS_endline(); -} - -/** - * set rate for given NMEA field - * @param field - name of NMEA field - * @param rate - rate in seconds (0 disables field) - * @return -1 if fails, rate if OK - */ -void block_field(const uint8_t *field){ - uint8_t buf[22]; - memcpy(buf, U("$PUBX,40,"), 9); - memcpy(buf+9, field, 3); - memcpy(buf+12, U(",0,0,0,0*"), 9); - buf[21] = 0; - write_with_checksum(buf); -} - - -/** - * Send starting sequences (get only RMC messages) - */ -void GPS_send_start_seq(){ - const uint8_t *GPmsgs[5] = {U("GSV"), U("GSA"), U("GGA"), U("GLL"), U("VTG")}; - int i; - for(i = 0; i < 5; ++i) - block_field(GPmsgs[i]); -} -/* -uint8_t *nextpos(uint8_t **buf, int pos){ - int i; - if(pos < 1) pos = 1; - for(i = 0; i < pos; ++i){ - *buf = ustrchr(*buf, ','); - if(!*buf) break; - ++(*buf); - } - return *buf; -} -#define NEXT() do{if(!nextpos(&buf, 1)) goto ret;}while(0) -#define SKIP(NPOS) do{if(!nextpos(&buf, NPOS)) goto ret;}while(0) -*/ -/** - * Parse answer from GPS module - * - * Recommended minimum specific GPS/Transit data - * $GPRMC,hhmmss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs - * 1 = UTC of position fix - * 2 = Data status (V=navigation receiver warning) - * 3 = Latitude of fix - * 4 = N or S - * 5 = Longitude of fix - * 6 = E or W - * 7 = Speed over ground in knots - * 8 = Cource over ground in degrees - * 9 = UT date - * 10 = Magnetic variation degrees (Easterly var. subtracts from true course) - * 11 = E or W - * 12 = Mode: N(bad), E(approx), A(auto), D(diff) - * 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B - */ -void GPS_parse_answer(uint8_t *buf){ - uint8_t *ptr; - if(strncmp(buf+3, U("RMC"), 3)){ // not RMC message - GPS_send_start_seq(); - return; - } - if(!checksum_true(buf)){ - DBG("Wrong chs\n"); - return; // wrong checksum - } - buf += 7; // skip header - if(*buf == ','){ // time unknown - GPS_status = GPS_WAIT; - return; - } - //P("time: "); - ptr = ustrchr(buf, ','); - *ptr++ = 0; - //P(buf); - if(*ptr == 'A'){ - GPS_status = GPS_VALID; - set_time(buf); - }else - GPS_status = GPS_NOT_VALID; -// buf = ustrchr(ptr, ','); -// P(" "); - P("\n"); -} - -/* - -void rmc(uint8_t *buf){ - //DBG("rmc: %s\n", buf); - int H, M, LO, LA, d, m, y, getdate = 0; - double S, longitude, lattitude, speed, track, mag; - char varn = 'V', north = '0', east = '0', mageast = '0', mode = 'N'; - sscanf((char*)buf, "%2d%2d%lf", &H, &M, &S); - NEXT(); - if(*buf != ',') varn = *buf; - if(varn != 'A') - PRINT("(data could be wrong)"); - else{ - PRINT("(data valid)"); - if(GP->date) getdate = 1; // as only we have valid data we show it to user - } - PRINT(" time: %02d:%02d:%05.2f", H, M, S); - PRINT(" timediff: %g", timediff(H, M, S)); - NEXT(); - sscanf((char*)buf, "%2d%lf", &LA, &lattitude); - NEXT(); - if(*buf != ','){ - north = *buf; - lattitude = (double)LA + lattitude / 60.; - if(north == 'S') lattitude = -lattitude; - PRINT(" latt: %g", lattitude); - Latt_mean += lattitude; - Latt_sq += lattitude*lattitude; - ++Latt_N; - } - NEXT(); - sscanf((char*)buf, "%3d%lf", &LO, &longitude); - NEXT(); - if(*buf != ','){ - east = *buf; - longitude = (double)LO + longitude / 60.; - if(east == 'W') longitude = -longitude; - PRINT(" long: %g", longitude); - Long_mean += longitude; - Long_sq += longitude*longitude; - ++Long_N; - } - NEXT(); - if(*buf != ','){ - sscanf((char*)buf, "%lf", &speed); - PRINT(" speed: %gknots", speed); - } - NEXT(); - if(*buf != ','){ - sscanf((char*)buf, "%lf", &track); - PRINT(" track: %gdeg,True", track); - } - NEXT(); - if(sscanf((char*)buf, "%2d%2d%2d", &d, &m, &y) == 3) - PRINT(" date(dd/mm/yy): %02d/%02d/%02d", d, m, y); - if(getdate) show_date(H,M,S,d,m,y); // show date & exit - NEXT(); - sscanf((char*)buf, "%lf,%c", &mag, &mageast); - if(mageast == 'E' || mageast == 'W'){ - if(mageast == 'W') mag = -mag; - PRINT(" magnetic var: %g", mag); - } - SKIP(2); - if(*buf != ','){ - mode = *buf; - PRINT(" mode: %c", mode); - } -ret: - PRINT("\n"); -} -*/ diff --git a/GPS/GPS.geany b/GPS/GPS.geany deleted file mode 100644 index 6f2dce9..0000000 --- a/GPS/GPS.geany +++ /dev/null @@ -1,37 +0,0 @@ -[file_prefs] -final_new_line=true -ensure_convert_new_lines=true -strip_trailing_spaces=true -replace_tabs=false - -[indentation] -indent_width=4 -indent_type=1 -indent_hard_tab_width=4 -detect_indent=false -detect_indent_width=false -indent_mode=3 - -[project] -name=GPS -base_path=/home/eddy/Docs/SAO/ELECTRONICS/STM32/c8t6/GPS/ - -[long line marker] -long_line_behaviour=1 -long_line_column=80 - -[files] -current_page=0 -FILE_NAME_0=2419;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fuser_proto.c;0;4 -FILE_NAME_1=1153;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fuser_proto.h;0;4 -FILE_NAME_2=5725;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fuart.c;0;4 -FILE_NAME_3=1269;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fuart.h;0;4 -FILE_NAME_4=925;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fmain.c;0;4 -FILE_NAME_5=1384;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fmain.h;0;4 -FILE_NAME_6=1188;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2FGPS.c;0;4 -FILE_NAME_7=875;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2FGPS.h;0;4 -FILE_NAME_8=2128;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2FGPS%2Fhardware_ini.c;0;4 -FILE_NAME_9=2589;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FGPS%2Fsrc%2Fmain.c;0;4 - -[VTE] -last_dir=/home/eddy/Docs/SAO/Cameras/FLI_camera/my/Mytakepic diff --git a/GPS/GPS.h b/GPS/GPS.h deleted file mode 100644 index d400864..0000000 --- a/GPS/GPS.h +++ /dev/null @@ -1,37 +0,0 @@ -/* - * GPS.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __GPS_H__ -#define __GPS_H__ - -typedef enum{ - GPS_WAIT // wait for satellites - ,GPS_NOT_VALID // time known, but not valid - ,GPS_VALID -} gps_status; - -extern gps_status GPS_status; - -void GPS_parse_answer(uint8_t *string); -void GPS_send_start_seq(); - -#endif // __GPS_H__ diff --git a/GPS/Makefile b/GPS/Makefile deleted file mode 100644 index 18f7a20..0000000 --- a/GPS/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = GPS -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/GPS/README b/GPS/README deleted file mode 100644 index d525426..0000000 --- a/GPS/README +++ /dev/null @@ -1,8 +0,0 @@ -NOT READY! - -GPS RTC - -written for chinese devboard based on STM32F103RBT6 - -Press H for help - diff --git a/GPS/cdcacm.c b/GPS/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/GPS/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/GPS/cdcacm.h b/GPS/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/GPS/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/GPS/hardware_ini.c b/GPS/hardware_ini.c deleted file mode 100644 index 1fe023e..0000000 --- a/GPS/hardware_ini.c +++ /dev/null @@ -1,108 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - /* - * Setup EXTI on PA4 (PPS input from GPS) - pull down - * EXTI on PA5 - also pull down (trigger for time measurement) - */ - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO4 | GPIO5); - //AFIO_EXTICR2 = 0; - exti_enable_request(EXTI4 | EXTI5); - // trigger on rising edge - exti_set_trigger(EXTI4 | EXTI5, EXTI_TRIGGER_RISING); - nvic_enable_irq(NVIC_EXTI4_IRQ); - nvic_enable_irq(NVIC_EXTI9_5_IRQ); -/* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN);*/ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - STK_RVR = STK_RVR_DEFAULT_VAL; // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -/* -// check buttons S2/S3 -void check_btns(){ - static uint8_t oldstate[2] = {1,1}; // old buttons state - uint8_t newstate[2], i; - static uint32_t Old_timer[2] = {0,0}; - newstate[0] = gpio_get(BTNS_PORT, BTN_S2_PIN) ? 1 : 0; - newstate[1] = gpio_get(BTNS_PORT, BTN_S3_PIN) ? 1 : 0; - for(i = 0; i < 2; i++){ - uint8_t new = newstate[i]; - // pause for 60ms - uint32_t O = Old_timer[i]; - if(O){ - if(Timer - O > 60 || O > Timer){ - P("Button S"); - usb_send('2' + i); - if(new) P("released"); - else P("pressed"); - newline(); - oldstate[i] = new; - Old_timer[i] = 0; - } - } - else if(new != oldstate[i]){ - Old_timer[i] = Timer; - } - } -} -*/ diff --git a/GPS/hardware_ini.h b/GPS/hardware_ini.h deleted file mode 100644 index ff0311f..0000000 --- a/GPS/hardware_ini.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * Buttons on devboard - */ -#define BTNS_PORT GPIOC -// PCO -- S2 -#define BTN_S2_PIN GPIO0 -// PC1 -- S3 -#define BTN_S3_PIN GPIO1 - -/* - * LEDS: PB9 for D1, PB8 for D2 - */ -#define LEDS_PORT GPIOB -#define LED_D1_PIN GPIO9 -#define LED_D2_PIN GPIO8 - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -void check_btns(); - -#endif // __HARDWARE_INI_H__ diff --git a/GPS/ld/devices.data b/GPS/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/GPS/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/GPS/ld/stm32f103x4.ld b/GPS/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/GPS/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103x6.ld b/GPS/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/GPS/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103x8.ld b/GPS/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/GPS/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xB.ld b/GPS/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/GPS/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xC.ld b/GPS/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/GPS/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xD.ld b/GPS/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/GPS/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xE.ld b/GPS/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/GPS/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xF.ld b/GPS/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/GPS/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/ld/stm32f103xG.ld b/GPS/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/GPS/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/GPS/main.c b/GPS/main.c deleted file mode 100644 index 4d9324a..0000000 --- a/GPS/main.c +++ /dev/null @@ -1,242 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "uart.h" -#include "GPS.h" - -volatile uint32_t Timer = 0; // milliseconds -volatile uint32_t msctr = 0; // global milliseconds for different purposes -usbd_device *usbd_dev; -volatile int32_t systick_val = 0; -volatile int32_t timer_val = 0; -volatile int clear_ST_on_connect = 1; - -volatile int need_sync = 1; - -volatile uint32_t last_corr_time = 0; // time of last PPS correction (seconds from midnight) - -// STK_CVR values for all milliseconds (RVR0) and last millisecond (RVR1) -volatile uint32_t RVR0 = STK_RVR_DEFAULT_VAL, RVR1 = STK_RVR_DEFAULT_VAL; - -curtime current_time = {25,61,61}; - -#define DIDNT_TRIGGERED (2000) -curtime trigger_time = {25, 61, 61}; -uint32_t trigger_ms = DIDNT_TRIGGERED; - -void time_increment(){ - Timer = 0; - if(current_time.H == 25) return; // Time not initialized - if(++current_time.S == 60){ - current_time.S = 0; - if(++current_time.M == 60){ - current_time.M = 0; - if(++current_time.H == 24) - current_time.H = 0; - } - } -} - -int main(){ - uint8_t *string; - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - UART_init(USART2); // init GPS UART - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - GPS_send_start_seq(); - - uint32_t trigrtm = 0; - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - if((string = check_UART2())){ - P(string); - GPS_parse_answer(string); - } - if(systick_val){ - P("Systick differs by "); - print_int(systick_val); - systick_val = 0; - P(", timer value: "); - print_int(timer_val); - P(", RVR0 = "); - print_int(RVR0); - P(", RVR1 = "); - print_int(RVR1); - P("\n"); - print_curtime(); - } - if(trigger_ms != DIDNT_TRIGGERED && (msctr < trigrtm || (msctr - trigrtm) > 100)){ - trigrtm = msctr; - P("Trigger time: "); - print_time(&trigger_time, trigger_ms); - trigger_ms = DIDNT_TRIGGERED; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - ++Timer; - ++msctr; - if(Timer == 999){ - STK_RVR = RVR1; - }else if(Timer == 1000){ - STK_RVR = RVR0; - time_increment(); - } - usb_send_buffer(); -} -// STK_CVR - current systick val -// STK_RVR - ticks till interrupt - 1 - -// PA4 interrupt - PPS signal -void exti4_isr(){ - uint32_t t = 0, ticks; - static uint32_t ticksavr = 0, N = 0; - if(EXTI_PR & EXTI4){ - // correct - systick_val = STK_CVR; - STK_CVR = RVR0; - timer_val = Timer; - Timer = 0; - systick_val = STK_RVR + 1 - systick_val; // Systick counts down! - if(timer_val < 10) timer_val += 1000; // our closks go faster than real - else if(timer_val < 990){ // something wrong - RVR0 = RVR1 = STK_RVR_DEFAULT_VAL; - STK_RVR = RVR0; - need_sync = 1; - goto theend; - }else - time_increment(); // ms counter less than 1000 - we need to increment time - t = current_time.H * 3600 + current_time.M * 60 + current_time.S; - if(clear_ST_on_connect){ - clear_ST_on_connect = 0; - }else{ - // || (last_corr_time == 86399 && t == 0) - if(t - last_corr_time == 1){ // PPS interval == 1s - ticks = systick_val + (timer_val-1)*(RVR0 + 1) + RVR1 + 1; - ++N; - ticksavr += ticks; - if(N > 20){ - ticks = ticksavr / N; - RVR0 = ticks / 1000 - 1; // main RVR value - STK_RVR = RVR0; - RVR1 = RVR0 + ticks % 1000; // last millisecond RVR value (with fine correction) - N = 0; - ticksavr = 0; - need_sync = 0; - } - }else{ - N = 0; - ticksavr = 0; - } - } - theend: - last_corr_time = t; - EXTI_PR = EXTI4; - } -} - -/** - * PA5 interrupt - print time - */ -void exti9_5_isr(){ - if(EXTI_PR & EXTI5){ - if(trigger_ms == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms = Timer; - memcpy(&trigger_time, ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI5; - } -} - -// pause function, delay in ms -void Delay(uint16_t time){ - uint32_t waitto = msctr + time; - while(msctr != waitto); -} - -/** - * set current time by buffer hhmmss - */ -void set_time(uint8_t *buf){ - inline uint8_t atou(uint8_t *b){ - return (b[0]-'0')*10 + b[1]-'0'; - } - uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS; - if(H > 23) H -= 24; - current_time.H = H; - current_time.M = atou(&buf[2]); - current_time.S = atou(&buf[4]); -} - -/** - * print time: Tm - time structure, T - milliseconds - */ -void print_time(curtime *Tm, uint32_t T){ - int S = Tm->S, M = Tm->M, H = Tm->H; - if(H < 10) usb_send('0'); - print_int(H); usb_send(':'); - if(M < 10) usb_send('0'); - print_int(M); usb_send(':'); - if(S < 10) usb_send('0'); - print_int(S); usb_send('.'); - if(T < 100) usb_send('0'); - if(T < 10) usb_send('0'); - print_int(T); - if(GPS_status == GPS_NOT_VALID) P(" (not valid)"); - if(need_sync) P(" need synchronisation"); - newline(); -} - -void print_curtime(){ - uint32_t T = Timer; - if(current_time.H < 24 && GPS_status != GPS_WAIT){ - P("Current time: "); - print_time(¤t_time, T); - }else - P("Waiting for satellites\n"); -} diff --git a/GPS/main.h b/GPS/main.h deleted file mode 100644 index fb24c30..0000000 --- a/GPS/main.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -extern void *memcpy(void *dest, const void *src, int n); - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -#define STK_RVR_DEFAULT_VAL (8999) -#define TIMEZONE_GMT_PLUS (3) - -typedef struct{ - uint8_t H; - uint8_t M; - uint8_t S; -} curtime; - -extern curtime current_time; -extern volatile uint32_t Timer; // global timer (milliseconds) -extern volatile int clear_ST_on_connect; // flag for clearing Systick counter on next PPS - -extern volatile int need_sync; - -void Delay(uint16_t time); -void set_time(uint8_t *buf); - -void print_time(curtime *T, uint32_t m); -void print_curtime(); - -#endif // __MAIN_H__ - diff --git a/GPS/sync.c b/GPS/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/GPS/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/GPS/sync.h b/GPS/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/GPS/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/GPS/uart.c b/GPS/uart.c deleted file mode 100644 index 0876706..0000000 --- a/GPS/uart.c +++ /dev/null @@ -1,265 +0,0 @@ -/* - * uart.c - functions to work with UART - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "uart.h" -#include "cdcacm.h" -#include "hardware_ini.h" - -// Buffers for Tx -static UART_buff TX_buffer[2]; // Tx buffers for all three ports -static UART_buff RX_buffer[2]; // Rx buffers for all three ports - -void fill_uart_RXbuff(uint32_t UART, uint8_t byte); - -/** - * Set UART speed - * @param lc - UART parameters or NULL for value from cdcacm.c (started - B115200,8,N,1) - */ -void UART_setspeed(uint32_t UART){ - usart_set_baudrate(UART, 9600); - usart_set_databits(UART, 8); - usart_set_stopbits(UART, USART_STOPBITS_1); - usart_set_parity(UART, USART_PARITY_NONE); - usart_set_flow_control(UART, USART_FLOWCONTROL_NONE); - usart_set_mode(UART, USART_MODE_TX_RX); -} - -/** - * Setup UART - */ -void UART_init(uint32_t UART){ - uint32_t irq, rcc, rccgpio, gpioport, gpiopin; - switch(UART){ - case USART2: // GPS UART - irq = NVIC_USART2_IRQ; // interrupt for given USART - rcc = RCC_USART2; // RCC timing of USART - rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output) - TX_buffer[1].end = 0; // reset counters - TX_buffer[1].start = 0; - RX_buffer[1].end = 0; - RX_buffer[1].start = 0; - // output pin setup - gpioport = GPIO_BANK_USART2_TX; - gpiopin = GPIO_USART2_TX; - break; - case USART1: - default: - irq = NVIC_USART1_IRQ; - rcc = RCC_USART1; - rccgpio = RCC_GPIOA; - TX_buffer[0].end = 0; - TX_buffer[0].start = 0; - RX_buffer[0].end = 0; - RX_buffer[0].start = 0; - gpioport = GPIO_BANK_USART1_TX; - gpiopin = GPIO_USART1_TX; - } - // enable clocking - rcc_periph_clock_enable(RCC_AFIO); // alternate functions - rcc_periph_clock_enable(rcc); // USART - rcc_periph_clock_enable(rccgpio); // GPIO pins - // enable output pin - gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin); - // enable IRQ - nvic_enable_irq(irq); - UART_setspeed(UART); - // Enable UART receive interrupt - USART_CR1(UART) |= USART_CR1_RXNEIE; - // Enable UART - usart_enable(UART); -} - -/* - * UART interrupts - */ -// common -void UART_isr(uint32_t UART){ - uint8_t bufidx = 0, data; - UART_buff *curbuff; - // Check if we were called because of RXNE - if(USART_SR(UART) & USART_SR_RXNE){ - // parse incoming byte - data = usart_recv(UART); - fill_uart_RXbuff(UART, data); - } - // Check if we were called because of TXE -> send next byte in buffer - if((USART_CR1(UART) & USART_CR1_TXEIE) && (USART_SR(UART) & USART_SR_TXE)){ - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - if(bufidx != curbuff->end){ // there's data in buffer - // Put data into the transmit register - usart_send(UART, curbuff->buf[bufidx]); - if(++(curbuff->start) == UART_BUF_DATA_SIZE){ // reload start - curbuff->start = 0; - } - }else{ // Disable the TXE interrupt, it's no longer needed - USART_CR1(UART) &= ~USART_CR1_TXEIE; - // empty indexes - curbuff->start = 0; - curbuff->end = 0; - } - } -} -// particular interrupt handlers -void usart1_isr(){ - UART_isr(USART1); -} -void usart2_isr(){ - UART_isr(USART2); -} - -// put byte into Tx buffer -void fill_uart_buff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx = 0, endidx; - if(!(USART_CR1(UART) & USART_CR1_UE)) return; // UART disabled - USART_CR1(UART) &= ~USART_CR1_TXEIE; // disable TX interrupt while buffer filling - while ((USART_SR(UART) & USART_SR_TXE) == 0); // wait until last byte send - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - case USART3: - bufidx = 2; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - endidx = curbuff->end; // end of data - curbuff->buf[endidx++] = byte; // put byte into buffer - // now check indexes - if(endidx != bufidx && endidx != UART_BUF_DATA_SIZE){ // all OK - there's enough place for data - (curbuff->end)++; // just increment index in buffer - }else{ // dangerous situation: possible overflow - if(endidx == UART_BUF_DATA_SIZE){ // end of buffer - if(bufidx != 0){ // no overflow - curbuff->end = 0; - goto end_of_fn; - } - } - // overflow: purge all data - bufidx = curbuff->start; // refresh data index - for(endidx = bufidx; endidx < UART_BUF_DATA_SIZE; endidx++) // first data porion - usart_send(UART, curbuff->buf[endidx]); - for(endidx = 0; endidx < bufidx; endidx++) // rest of data - usart_send(UART, curbuff->buf[endidx]); - curbuff->start = 0; - curbuff->end = 0; - return; - } - end_of_fn: - // enable interrupts to send data from buffer - USART_CR1(UART) |= USART_CR1_TXEIE; -} - -/** - * send data over UART - one function for each uart - * @param byte - one byte to put in UART queue - */ -void uart1_send(uint8_t byte){ - fill_uart_buff(USART1, byte); -} -void uart2_send(uint8_t byte){ - fill_uart_buff(USART2, byte); -} -/* -UART_buff *get_uart_buffer(uint32_t UART){ - switch(UART){ - case USART1: - return &RX_buffer[0]; - break; - case USART2: - return &RX_buffer[1]; - break; - default: // error - return - return NULL; - } - return NULL; -}*/ - - -/** - * Check whether UART2 have a full text line - * @return string with data if data ready or NULL - */ -uint8_t *check_UART2(){ - static int oldlen = 0; - static uint8_t buf[UART_BUF_DATA_SIZE+1]; - UART_buff *curbuff = &RX_buffer[1]; - uint8_t datalen = curbuff->end; // length of data in buffer - here we use param "end" - if(!datalen) return NULL; // buffer is empty - if(oldlen != datalen){ - if(curbuff->buf[curbuff->end-1] != '\n'){ // string not full - oldlen = datalen; - return NULL; - }else{ // full string - copy it to buffer & clear indexes - memcpy(buf, curbuff->buf, datalen); - buf[datalen] = 0; - oldlen = curbuff->end = 0; - return buf; - } - } - return NULL; -} - -/** - * Fill data in RX buffer to prepare it for further work - * we don't use "start" parameter here, it's 0 always - * @param UART - device to fill buffer - * @param byte - data byte - */ -void fill_uart_RXbuff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx; - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &RX_buffer[bufidx]; - if(curbuff->end == UART_BUF_DATA_SIZE){ // end of buffer - forget about data - curbuff->end = 0; - return; - } - curbuff->buf[curbuff->end++] = byte; // put byte into buffer -} diff --git a/GPS/uart.h b/GPS/uart.h deleted file mode 100644 index 85715ca..0000000 --- a/GPS/uart.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * uart.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __UART_H__ -#define __UART_H__ - -// Size of buffers -#define UART_BUF_DATA_SIZE 128 - -typedef struct { - uint8_t buf[UART_BUF_DATA_SIZE]; - uint8_t start; // index from where to start reading - uint8_t end; // index from where to start writing -} UART_buff; - -void UART_init(uint32_t UART); -void UART_setspeed(uint32_t UART); - -void fill_uart_buff(uint32_t UART, uint8_t byte); -void uart1_send(uint8_t byte); -void uart2_send(uint8_t byte); - -uint8_t *check_UART2(); - -UART_buff *get_uart_buffer(uint32_t UART); - -#endif // __UART_H__ diff --git a/GPS/user_proto.c b/GPS/user_proto.c deleted file mode 100644 index 334b0cb..0000000 --- a/GPS/user_proto.c +++ /dev/null @@ -1,204 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "GPS.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("C\tclear SysTick on PPS\n"); - P("H\tshow this help\n"); -// P("I\ttest entering integer value\n"); - P("S\tSend GPS starting sequence\n"); - P("T\tshow current approx. time\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'C': - clear_ST_on_connect = 1; - break; - case 'H': // show help - help(); - break; -/* case 'I': // enter integer & show its value - I = show_int; - READINT(); - break;*/ - case 'S': - GPS_send_start_seq(); - break; - case 'T': - print_curtime(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/GPS/user_proto.h b/GPS/user_proto.h deleted file mode 100644 index 69bf771..0000000 --- a/GPS/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/Jeep_generator/Makefile b/Jeep_generator/Makefile deleted file mode 100644 index 2aab10c..0000000 --- a/Jeep_generator/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = jeep_generator -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103xB.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -O3 -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/Jeep_generator/README b/Jeep_generator/README deleted file mode 100644 index f8cf9c2..0000000 --- a/Jeep_generator/README +++ /dev/null @@ -1,8 +0,0 @@ -Jeep crankshaft signals generator - -Speed from 200 to 6000RPM -Buttons "+" and "-", LEDS "MIN" and "MAX" - -written for chinese devboard based on STM32F103RBT6 - -Press H for help in terminal diff --git a/Jeep_generator/cdcacm.c b/Jeep_generator/cdcacm.c deleted file mode 100644 index 34c33bc..0000000 --- a/Jeep_generator/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "SAO RAS, Emelianov E.V.", - "Jeep generator", - "0.0.1", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/Jeep_generator/cdcacm.h b/Jeep_generator/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/Jeep_generator/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/Jeep_generator/hardware_ini.c b/Jeep_generator/hardware_ini.c deleted file mode 100644 index 7442e5f..0000000 --- a/Jeep_generator/hardware_ini.c +++ /dev/null @@ -1,68 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_PLUS_PIN | BTN_MINUS_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_LOW_PIN | LED_UPPER_PIN); - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_PLUS_PIN | BTN_MINUS_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_LOW_PIN | LED_UPPER_PIN); - // Tacting output (opendrain) - gpio_set_mode(OUTP_PORT, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - OUTP_PIN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - diff --git a/Jeep_generator/hardware_ini.h b/Jeep_generator/hardware_ini.h deleted file mode 100644 index 018f038..0000000 --- a/Jeep_generator/hardware_ini.h +++ /dev/null @@ -1,80 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * Buttons "+"/"-" - */ -#define BTNS_PORT GPIOA -// PA10 -- increase speed -#define BTN_PLUS_PIN GPIO10 -// PA9 -- decrease speed -#define BTN_MINUS_PIN GPIO9 - -/* - * Tacting out - PA4 - */ -#define OUTP_PORT GPIOA -#define OUTP_PIN GPIO4 - -/* - * LEDS: PA0 for bottom, PA1 for upper limits - */ -#define LEDS_PORT GPIOA -#define LED_LOW_PIN GPIO0 -#define LED_UPPER_PIN GPIO1 - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/Jeep_generator/jeep_generator.bin b/Jeep_generator/jeep_generator.bin deleted file mode 100755 index e65ab1e..0000000 Binary files a/Jeep_generator/jeep_generator.bin and /dev/null differ diff --git a/Jeep_generator/ld/stm32f103x4.ld b/Jeep_generator/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/Jeep_generator/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103x6.ld b/Jeep_generator/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/Jeep_generator/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103x8.ld b/Jeep_generator/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/Jeep_generator/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xB.ld b/Jeep_generator/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/Jeep_generator/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xC.ld b/Jeep_generator/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/Jeep_generator/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xD.ld b/Jeep_generator/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/Jeep_generator/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xE.ld b/Jeep_generator/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/Jeep_generator/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xF.ld b/Jeep_generator/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/Jeep_generator/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/ld/stm32f103xG.ld b/Jeep_generator/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/Jeep_generator/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Jeep_generator/main.c b/Jeep_generator/main.c deleted file mode 100644 index 7336d53..0000000 --- a/Jeep_generator/main.c +++ /dev/null @@ -1,122 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "timer.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; -void check_btns(); - -int main(){ - uint32_t Old_timer = 0; - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - GPIO_init(); - usb_disconnect(); // turn off USB while initializing all - // USB - usbd_dev = USB_init(); - // SysTick is a system timer with 1ms period - SysTick_init(); - tim2_init(); // start transmission - usb_connect(); // turn on USB - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - check_btns(); - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - -// check buttons +/- -void check_btns(){ - static uint8_t oldstate[2] = {1,1}, done[2] = {0,0}; // old buttons state, event handler flag - uint8_t i; - const char ltr[2] = {'+', '-'}; - const uint32_t pins[2] = {BTN_PLUS_PIN, BTN_MINUS_PIN}; - static uint32_t Old_timer[2] = {0,0}; - for(i = 0; i < 2; i++){ - uint8_t new = gpio_get(BTNS_PORT, pins[i]) ? 1 : 0; - // whe check button state at 3ms after event; don't mind events for 50ms after first - uint32_t O = Old_timer[i]; - if(!O){ // no previous pauses - // button was pressed or released just now or holded - if(new != oldstate[i] || !new){ - Old_timer[i] = Timer; - oldstate[i] = new; - } - }else{ // noice or real event? - if(Timer - O < 3){ // less than 3ms from last event - if(new != oldstate[i]){ // noice or button released - oldstate[i] = new; - Old_timer[i] = 0; - } - continue; - } - // more than 50ms from last event - if(Timer - O > 50 || O > Timer){ // clear new events masking - oldstate[i] = new; - Old_timer[i] = 0; - done[i] = 0; - }else{ - if(!new && !done[i]){ // button pressed: just now or hold - usb_send(ltr[i]); - newline(); - if(i) decrease_speed(); // "+" - else increase_speed(); - done[i] = 1; - } - } - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/Jeep_generator/main.h b/Jeep_generator/main.h deleted file mode 100644 index 5b9ef56..0000000 --- a/Jeep_generator/main.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -//#include -#include -#include -#include -#include -#include -#include -//#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/Jeep_generator/sync.c b/Jeep_generator/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/Jeep_generator/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/Jeep_generator/sync.h b/Jeep_generator/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/Jeep_generator/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/Jeep_generator/timer.c b/Jeep_generator/timer.c deleted file mode 100644 index 2e73b8e..0000000 --- a/Jeep_generator/timer.c +++ /dev/null @@ -1,117 +0,0 @@ -/* - * timer.c - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "timer.h" -#include "user_proto.h" // for print_int - -// current speed -uint16_t current_RPM = 0; -void get_RPM(); -uint16_t get_ARR(uint32_t RPM); - -// pulses: 16 1/0, 4 1/1, 16 1/0, 4 0/0, -const uint8_t pulses[] = { - 1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0, - 1,1,1,1,1,1,1,1, - 1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0,1,0, - 0,0,0,0,0,0,0,0}; -const int pulsesLen = sizeof(pulses) - 1; - -void tim2_init(){ - // init TIM2 - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timer have frequency of 1MHz - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 36 = 2MHz - TIM2_PSC = 35; // we need double freq to serve both halfs of signal - TIM2_ARR = get_ARR(MIN_RPM); - TIM2_DIER = TIM_DIER_UDE | TIM_DIER_UIE; - nvic_enable_irq(NVIC_TIM2_IRQ); - TIM2_CR1 |= TIM_CR1_CEN; - get_RPM(); -} - -void tim2_isr(){ - static uint16_t ctr = 0; - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - if(ctr > pulsesLen) ctr = 0; - if(pulses[++ctr]) - GPIO_BSRR(OUTP_PORT) = OUTP_PIN; - else - GPIO_BSRR(OUTP_PORT) = OUTP_PIN << 16; - } - TIM2_SR = 0; -} - -/** - * Calculate motor speed in RPM - * RPM = 1/tim2_arr / 40 * 60 - */ -void get_RPM(){ - uint32_t R = 3000000 / (uint32_t)TIM2_ARR; - current_RPM = R/2; - //current_RPM = R; - //current_RPM >>= 1; // x/2 != x>>1, WTF? -} - -// calculate TIM2_ARR by RPM -uint16_t get_ARR(uint32_t RPM){ - uint32_t R = 3000000 / RPM; - R /= 2; - //R >>= 1; - return (uint16_t)R; -} - -/** - * Change "rotation speed" by 100rpm - */ -void increase_speed(){ - if(current_RPM == MAX_RPM) return; - current_RPM += 100; - if(current_RPM > MAX_RPM){ // set LED "MAX" - current_RPM = MAX_RPM; - TIM2_ARR = get_ARR(current_RPM); - gpio_clear(LEDS_PORT, LED_UPPER_PIN); - }else{ - TIM2_ARR = get_ARR(current_RPM); - get_RPM(); // recalculate speed - gpio_set(LEDS_PORT, LED_UPPER_PIN); - } - gpio_set(LEDS_PORT, LED_LOW_PIN); - print_int(current_RPM); -} - -void decrease_speed(){ - if(current_RPM == MIN_RPM) return; - current_RPM -= 100; - if(current_RPM < MIN_RPM){ // set LED "MIN" - current_RPM = MIN_RPM; - TIM2_ARR = get_ARR(current_RPM); - gpio_clear(LEDS_PORT, LED_LOW_PIN); - }else{ - TIM2_ARR = get_ARR(current_RPM); - get_RPM(); - gpio_set(LEDS_PORT, LED_LOW_PIN); - } - gpio_set(LEDS_PORT, LED_UPPER_PIN); - print_int(current_RPM); -} diff --git a/Jeep_generator/timer.h b/Jeep_generator/timer.h deleted file mode 100644 index 855d2d4..0000000 --- a/Jeep_generator/timer.h +++ /dev/null @@ -1,43 +0,0 @@ -/* - * timer.h - * - * Copyright 2016 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __TIMER_H__ -#define __TIMER_H__ - -#include "main.h" -#include "hardware_ini.h" - -//~ // 180rpm - 120Hz, T/2=8333us -//~ #define TM2_MIN_SPEED (8333) -//~ // 6000rpm - 4kHz, T/2=250us -//~ #define TM2_MAX_SPEED (250) -// max & min rotation speed -#define MAX_RPM (6000) -#define MIN_RPM (200) - - -void tim2_init(); -void increase_speed(); -void decrease_speed(); - -extern uint16_t current_RPM; - -#endif // __TIMER_H__ diff --git a/Jeep_generator/user_proto.c b/Jeep_generator/user_proto.c deleted file mode 100644 index 2827ddd..0000000 --- a/Jeep_generator/user_proto.c +++ /dev/null @@ -1,107 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "timer.h" - - -void help(){ - P("g\tShow this help\n"); - P("t\tShow current approx. time\n"); - P("+\tIncrease speed by 100\n"); - P("-\tDecrease speed by 100\n"); - P("g\tGet current speed\n"); -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - int i = 0; - for(; i < len; ++i){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'h': // show help - help(); - break; - case 't': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case 'g': - P("Current speed: "); - print_int(current_RPM); - P("rpm\n"); - break; - case '+': - increase_speed(); - break; - case '-': - decrease_speed(); - break; - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/Jeep_generator/user_proto.h b/Jeep_generator/user_proto.h deleted file mode 100644 index 4201c68..0000000 --- a/Jeep_generator/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/README b/README index ea89d53..931325d 100644 --- a/README +++ b/README @@ -1,22 +1,5 @@ These are my simple snippets for STM32 (compiled with libopencm3) Be carefull: due to API changes these projects will compile only with opencm3 from archive libopencm3.ori.tgz -- 1_wire - pseudo-hardware realisation of 1-wire protocol -- canon_lens - Canon EF lens management -- client-term is terminal client used instead of "com" -- distance_meters - Distance meter based on ultrasonic sensor HC-SR04 & Sharp 2Y0A02 IR sensor -- DMA_GPIO - simple 8-bit FSMC emulation with DMA -- GPIO_TIM - simple FSMC emulation by timer interrupts -- GPS - first approximation to GPS clock -- GPS+ultrasonic - GPS-based timelapse tool allows to get precision (milliseconds) time for four types of sensors -- hid_mouse_keyboard - a very simple example of simultaneous STM32 work as compound USB-HID device: usb & mouse -- Jeep_generator - krancshaft signal emulator for Jeep -- keyboard_snippet - This snippet allows to emulate USB keyboard -- matrix_keyboard - connect simple matrix keyboard 3x3 or 4x4 to computer as regular USB keyboard -- nokia5110 - print on a nokia5110 display text sent by terminal -- simple_cdc - simplest USB-CDC working in char-mode, press H for help (another commands are for LEDs switching and test of integer input) -- stepper_motion - move stepper motor -- Timelapse_keyboard - USB-keyboard emulator that prints precision time of different sensors and switches (for sport competitions) -- ultrasonic - Distance meter based on ultrasonic sensor HC-SR04 & Sharp 2Y0A02 IR sensor -- USBCDC_template - Template of USB-CDC - +F0 - for STM32F042 and STM32F030 +F1 - for STM32F103 diff --git a/Timelapse_keyboard/GPS.c b/Timelapse_keyboard/GPS.c deleted file mode 100644 index b684f42..0000000 --- a/Timelapse_keyboard/GPS.c +++ /dev/null @@ -1,162 +0,0 @@ -/* - * GPS.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "GPS.h" -#include "uart.h" - -#define GPS_endline() do{GPS_send_string((uint8_t*)"\r\n");}while(0) -#define U(arg) ((uint8_t*)arg) - -gps_status GPS_status = GPS_WAIT; - -void GPS_send_string(uint8_t *str){ - while(*str) - fill_uart_buff(USART2, *str++); -} - -int strncmp(const uint8_t *one, const uint8_t *two, int n){ - int diff = 0; - do{ - diff = (int)(*one++) - (int)(*two++); - }while(--n && diff == 0); - return diff; -} - -uint8_t *ustrchr(uint8_t *str, uint8_t symbol){ -// uint8_t *ptr = str; - do{ - if(*str == symbol) return str; - }while(*(++str)); - return NULL; -} - -uint8_t hex(uint8_t n){ - return ((n < 10) ? (n+'0') : (n+'A'-10)); -} - -/** - * Check checksum - */ -int checksum_true(uint8_t *buf){ - uint8_t *eol; - uint8_t checksum = 0, cs[3]; - if(*buf != '$' || !(eol = ustrchr(buf, '*'))){ - return 0; - } - while(++buf != eol) - checksum ^= *buf; - ++buf; - cs[0] = hex(checksum >> 4); - cs[1] = hex(checksum & 0x0f); - if(buf[0] == cs[0] && buf[1] == cs[1]) - return 1; - return 0; -} - -void send_chksum(uint8_t chs){ - fill_uart_buff(USART2, hex(chs >> 4)); - fill_uart_buff(USART2, hex(chs & 0x0f)); -} -/** - * Calculate checksum & write message to port - * @param buf - command to write (with leading $ and trailing *) - * return 0 if fails - */ -void write_with_checksum(uint8_t *buf){ - uint8_t checksum = 0; - GPS_send_string(buf); - ++buf; // skip leaders - do{ - checksum ^= *buf++; - }while(*buf && *buf != '*'); - send_chksum(checksum); - GPS_endline(); -} - -/** - * set rate for given NMEA field - * @param field - name of NMEA field - * @param rate - rate in seconds (0 disables field) - * @return -1 if fails, rate if OK - */ -void block_field(const uint8_t *field){ - uint8_t buf[22]; - memcpy(buf, U("$PUBX,40,"), 9); - memcpy(buf+9, field, 3); - memcpy(buf+12, U(",0,0,0,0*"), 9); - buf[21] = 0; - write_with_checksum(buf); -} - - -/** - * Send starting sequences (get only RMC messages) - */ -void GPS_send_start_seq(){ - const uint8_t *GPmsgs[5] = {U("GSV"), U("GSA"), U("GGA"), U("GLL"), U("VTG")}; - int i; - for(i = 0; i < 5; ++i) - block_field(GPmsgs[i]); -} - -/** - * Parse answer from GPS module - * - * Recommended minimum specific GPS/Transit data - * $GPRMC,hhmmss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs - * 1 = UTC of position fix - * 2 = Data status (V=navigation receiver warning) - * 3 = Latitude of fix - * 4 = N or S - * 5 = Longitude of fix - * 6 = E or W - * 7 = Speed over ground in knots - * 8 = Cource over ground in degrees - * 9 = UT date - * 10 = Magnetic variation degrees (Easterly var. subtracts from true course) - * 11 = E or W - * 12 = Mode: N(bad), E(approx), A(auto), D(diff) - * 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B - */ -void GPS_parse_answer(uint8_t *buf){ - uint8_t *ptr; - if(strncmp(buf+3, U("RMC"), 3)){ // not RMC message - GPS_send_start_seq(); - return; - } - if(!checksum_true(buf)){ - return; // wrong checksum - } - buf += 7; // skip header - if(*buf == ','){ // time unknown - GPS_status = GPS_WAIT; - return; - } - ptr = ustrchr(buf, ','); - *ptr++ = 0; - if(*ptr == 'A'){ - GPS_status = GPS_VALID; - }else{ - GPS_status = GPS_NOT_VALID; - } - set_time(buf); -} diff --git a/Timelapse_keyboard/GPS.h b/Timelapse_keyboard/GPS.h deleted file mode 100644 index d400864..0000000 --- a/Timelapse_keyboard/GPS.h +++ /dev/null @@ -1,37 +0,0 @@ -/* - * GPS.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __GPS_H__ -#define __GPS_H__ - -typedef enum{ - GPS_WAIT // wait for satellites - ,GPS_NOT_VALID // time known, but not valid - ,GPS_VALID -} gps_status; - -extern gps_status GPS_status; - -void GPS_parse_answer(uint8_t *string); -void GPS_send_start_seq(); - -#endif // __GPS_H__ diff --git a/Timelapse_keyboard/Makefile b/Timelapse_keyboard/Makefile deleted file mode 100644 index 5c38f09..0000000 --- a/Timelapse_keyboard/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = timelapse -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -# add -DULTRASONIC to compile with ultrasonic distance-meter support -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/Timelapse_keyboard/Readme.md b/Timelapse_keyboard/Readme.md deleted file mode 100644 index e124af5..0000000 --- a/Timelapse_keyboard/Readme.md +++ /dev/null @@ -1,35 +0,0 @@ -## Time-lapse as USB HID keyboard - -This tool allow to get precision time of events: pressing switch, -changing distance measured by ultrasonic or infrared sensor, -laser light disappearing on photoresistor - -Just connect board to any device with USB keyboard support, after some time -(needed to establish GPS connection and precision timer setup) it will simulate -keyboard on which somebody types time of sensors' state changing - - -#### Sensors supprorted -* SHARP GP2Y0A02YK - infrared distance-meter -* HCSR04 - ultrasonic distance-meter -* simple switch-button -* photoresistor + laser - -To get precision time this tool use GPS module (NEO-6M) - -#### Connection diagram -| Pin | Function | -| :--: | :-------- | -| PA0 | Infrared sensor data | -| PA1 | Laser photoresistor data | -| PA2 | GPS Rx (MCU Tx) | -| PA3 | GPS Tx (MCU Rx) | -| PA4 | GPS PPS signal | -| PA5 | Trigger (button) switch | -| PB10 | Ultrasonic "TRIG" pin | -| PB11 | Ultrasonic "ECHO" pin | - -#### Powering devices -* To power up GPS module you can use +5V or +3.3V. -* Ultrasonic & Infrared sensors need +5V power. -* Photoresistor should be connected to +3.3V by one pin, another pin (data) should be pulled to ground by 1kOhm resisror diff --git a/Timelapse_keyboard/adc.c b/Timelapse_keyboard/adc.c deleted file mode 100644 index 1467a67..0000000 --- a/Timelapse_keyboard/adc.c +++ /dev/null @@ -1,127 +0,0 @@ -/* - * adc.c - functions for Sharp 2Y0A02 distance meter & photosensor - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "adc.h" -#include "main.h" -#include "usbkeybrd.h" - -uint16_t ADC_value[ADC_CHANNEL_NUMBER]; // Values of ADC -uint16_t ADC_trig_val[2]; // -//- at trigger time - -void init_adc_sensor(){ - // we will use ADC1 channel 0 for IR sensor & ADC1 channel 1 for laser's photoresistor - uint8_t adc_channel_array[ADC_CHANNEL_NUMBER] = {0,1,6}; - // Make sure the ADC doesn't run during config - adc_off(ADC1); - // enable ADC & PA0/PA1 clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN | RCC_APB2ENR_IOPAEN); - rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4); - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0 | GPIO1); - rcc_periph_clock_enable(RCC_DMA1); // enable DMA for ADC values storing - // Configure ADC as continuous scan mode with DMA - ADC1_CR1 = ADC_CR1_SCAN; // enable scan mode - // set sample time on channels 1&2: 239.5 cycles for better results - ADC1_SMPR2 = 0x3f; - dma_channel_reset(DMA1, DMA_CHANNEL1); - DMA1_CPAR1 = (uint32_t) &(ADC_DR(ADC1)); - DMA1_CMAR1 = (uint32_t) ADC_value; - DMA1_CNDTR1 = ADC_CHANNEL_NUMBER; - DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT - | DMA_CCR_CIRC | DMA_CCR_PL_HIGH | DMA_CCR_EN; - // continuous conv, enable ADC & DMA - ADC1_CR2 = ADC_CR2_CONT | ADC_CR2_ADON | ADC_CR2_DMA; - // set channels - adc_set_regular_sequence(ADC1, ADC_CHANNEL_NUMBER, adc_channel_array); - // reset calibration registers & start calibration - ADC1_CR2 |= ADC_CR2_RSTCAL; - while(ADC1_CR2 & ADC_CR2_RSTCAL); // wait for registers reset - ADC1_CR2 |= ADC_CR2_CAL; - while(ADC1_CR2 & ADC_CR2_CAL); // wait for calibration ends - nvic_enable_irq(NVIC_ADC1_2_IRQ); - ADC1_CR2 |= ADC_CR2_SWSTART; - // turn on ADC - to do it we need set ADC_CR2_ADON again! - ADC1_CR2 |= ADC_CR2_ADON; -} - -adwd_stat adc_status[ADC_CHANNEL_NUMBER] = {ADWD_MID, ADWD_MID, ADWD_MID}; - - -// levels for thresholding -/* - * Infrared sensor calibration - * distance, cm ADC value, ADU (+- 3%) - * 0 100 - * 10 3300 - * 20 3170 - * 30 2400 - * 40 1720 - * 50 1400 - * 60 1200 - * 70 1100 - * 80 980 - * 90 860 - * 100 760 - * 145 490 - * - * IR distance \approx 74000/ADU (cm) - * - * Laser photoresistor: 2700 ADU in laser beam, 1760 in light room, 300 when darkened - */ -const uint16_t ADC_lowlevel[2] = {0, 2000}; // signal if ADC value < lowlevel -const uint16_t ADC_midlevel[2] = {400, 2500}; // when transit through midlevel set status as ADWD_MID -const uint16_t ADC_highlevel[2]= {800, 5000}; // signal if ADC value > highlevel - -void poll_ADC(){ - int i; - for(i = 0; i < 2; ++i){ - uint32_t adcms = adc_ms[i]; - uint16_t val = ADC_value[i]; - adwd_stat st = adc_status[i]; - if(adcms == DIDNT_TRIGGERED){ - if(val > ADC_highlevel[i]){ // watchdog event on high level - if(st != ADWD_HI){ - adc_ms[i] = Timer; - memcpy(&adc_time[i], ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_HI; - ADC_trig_val[i] = val; - } - }else if(val < ADC_lowlevel[i]){ // watchdog event on low level - if(st != ADWD_LOW){ - adc_ms[i] = Timer; - memcpy(&adc_time[i], ¤t_time, sizeof(curtime)); - adc_status[i] = ADWD_LOW; - ADC_trig_val[i] = val; - } - } - } - if((st == ADWD_HI && val < ADC_midlevel[i]) || - (st == ADWD_LOW && val > ADC_midlevel[i])){ - adc_status[i] = ADWD_MID; - if(adcms != DIDNT_TRIGGERED){ - int32_t timediff = Timer - adcms; - if(timediff < 0) timediff += 1000; - if(timediff <= ADC_NOICE_TIMEOUT){ // remove noice - adc_ms[i] = DIDNT_TRIGGERED; - } - } - } - } -} diff --git a/Timelapse_keyboard/adc.h b/Timelapse_keyboard/adc.h deleted file mode 100644 index 7692187..0000000 --- a/Timelapse_keyboard/adc.h +++ /dev/null @@ -1,55 +0,0 @@ -/* - * adc.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SHARP_H__ -#define __SHARP_H__ - -#include - -extern uint16_t ADC_value[]; -extern uint16_t ADC_trig_val[]; - -typedef enum{ - ADWD_LOW, // watchdog at low-level - ADWD_MID, // normal state - ADWD_HI // watchdog at high-level -} adwd_stat; - -extern adwd_stat adc_status[]; - -// pause for noice removal -#define ADC_NOICE_TIMEOUT (5) - -// channels: 0 - IR, 1 - laser's photoresistor, 6 - 12V -#define ADC_CHANNEL_NUMBER (3) -// 10.8V - power alarm (resistor divider: 10kOhm : (3.0kOhm || zener), U/100=2/5*ADC_value) -// (11.15Vin == 2.25Vout) -#define POWER_ALRM_LEVEL (2705) -// critical voltage: approx 8V -#define POWER_CRITICAL_LEVEL (2000) -// 11.5V - power OK -#define GOOD_POWER_LEVEL (2880) - -void init_adc_sensor(); -void poll_ADC(); - -#endif // __SHARP_H__ diff --git a/Timelapse_keyboard/hardware_ini.c b/Timelapse_keyboard/hardware_ini.c deleted file mode 100644 index 7a5b69c..0000000 --- a/Timelapse_keyboard/hardware_ini.c +++ /dev/null @@ -1,133 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" -#include - -/** - * Init timer4 channel 4 (beeper) - * -void tim4_init(){ - // setup PB9 - push/pull - gpio_set_mode(GPIO_BANK_TIM4_CH4, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM4_CH4); - rcc_periph_clock_enable(RCC_TIM4); - timer_reset(TIM4); - // timer have frequency of 1MHz to have ability of period changing with 1us discrete - // 36MHz of APB1 - timer_set_mode(TIM4, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM4_PSC = 71; // prescaler is (div - 1) - TIM4_ARR = BEEPER_PERIOD - 1; - TIM4_CCR4 = BEEPER_PERIOD/2; // PWM 50/50% - TIM4_DIER = TIM_DIER_UIE; - // PWM_OUT for TIM4_CH4 - TIM4_CCMR2 = TIM_CCMR2_CC4S_OUT | TIM_CCMR2_OC4M_PWM1; - nvic_enable_irq(NVIC_TIM4_IRQ); -} - -uint32_t beeper_counter = 1; -*/ -/** - * Run beeper for BEEPER_AMOUNT pulses - * -void beep(){ - TIM4_CR1 = 0; // stop timer if it was runned - beeper_counter = BEEPER_AMOUNT; - TIM4_SR = 0; // clear all flags - TIM4_CR1 = TIM_CR1_CEN; -} - -void tim4_isr(){ - // No signal - if(TIM4_SR & TIM_SR_UIF){ // update interrupt - TIM4_SR = 0; - if(--beeper_counter == 0){ // done! Turn off timer - TIM2_CR1 = 0; - } - } -} -*/ - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - // enable clocking for all ports, APB2 & AFIO (we need AFIO to remap JTAG pins) - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN | RCC_APB2ENR_AFIOEN); - // turn off SWJ/JTAG - AFIO_MAPR = AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF; - /* - * Setup EXTI on PA4 (PPS input from GPS) - pull down - * EXTI on PA5 - also pull down (trigger for time measurement) - */ - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO4 | GPIO5); - //AFIO_EXTICR2 = 0; - exti_enable_request(EXTI4 | EXTI5); - // trigger on rising edge - exti_set_trigger(EXTI4 | EXTI5, EXTI_TRIGGER_RISING); - nvic_enable_irq(NVIC_EXTI4_IRQ); - nvic_enable_irq(NVIC_EXTI9_5_IRQ); - // LEDS: opendrain output (&turn all OFF) - gpio_set(LEDS_Y_PORT, LEDS_Y1_PIN | LEDS_Y2_PIN); - gpio_set_mode(LEDS_Y_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_Y1_PIN | LEDS_Y2_PIN); - gpio_set(LEDS_G_PORT, LEDS_G1_PIN | LEDS_G2_PIN); - gpio_set_mode(LEDS_G_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_G1_PIN | LEDS_G2_PIN); - gpio_set(LEDS_R_PORT, LEDS_R1_PIN | LEDS_R2_PIN); - gpio_set_mode(LEDS_R_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_R1_PIN | LEDS_R2_PIN); - // beeper pin: push-pull - gpio_set(BEEPER_PORT, BEEPER_PIN); - gpio_set_mode(BEEPER_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, BEEPER_PIN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/** - * PA5 interrupt - print time at button/switch trigger - */ -void exti9_5_isr(){ - if(EXTI_PR & EXTI5){ - if(trigger_ms == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms = Timer; - memcpy(&trigger_time, ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI5; - } -} diff --git a/Timelapse_keyboard/hardware_ini.h b/Timelapse_keyboard/hardware_ini.h deleted file mode 100644 index c207f77..0000000 --- a/Timelapse_keyboard/hardware_ini.h +++ /dev/null @@ -1,84 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - * Tim2 - ultrasonic - * Tim4 - beeper - */ - -//void tim4_init(); -//void beep(); -void GPIO_init(); -void SysTick_init(); - -// yellow LEDs: PA11, PA12; Y1- - trigr, Y2 - PPS -#define LEDS_Y_PORT GPIOA -#define LEDS_Y1_PIN GPIO13 -#define LEDS_Y2_PIN GPIO15 -// green LEDs: PB7, PB8; G1 - GPS rdy -#define LEDS_G_PORT GPIOB -#define LEDS_G1_PIN GPIO7 -#define LEDS_G2_PIN GPIO8 -// red LEDs: PB6, PB5; R2 - power -#define LEDS_R_PORT GPIOB -#define LEDS_R1_PIN GPIO6 -#define LEDS_R2_PIN GPIO5 -// beeper - PB9 -#define BEEPER_PORT GPIOB -#define BEEPER_PIN GPIO9 - -/* -// beeper period (in microseconds) - approx 440 Hz -#define BEEPER_PERIOD (2273) -// amount of beeper pulses (after this walue it will be off) - near 2seconds -#define BEEPER_AMOUNT (880) -*/ -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - - -#endif // __HARDWARE_INI_H__ diff --git a/Timelapse_keyboard/keycodes.c b/Timelapse_keyboard/keycodes.c deleted file mode 100644 index 7d9d2f5..0000000 --- a/Timelapse_keyboard/keycodes.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * keycodes.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "keycodes.h" -/* - * Keyboard buffer: - * buf[0]: MOD - * buf[1]: reserved - * buf[2]..buf[7] - keycodes 1..6 - */ -static uint8_t buf[8] = {0,0,0,0,0,0,0,0}; - -#define _(x) (x|0x80) -// array for keycodes according to ASCII table; MSB is MOD_SHIFT flag -static const uint8_t keycodes[] = { - // space !"#$%&' - KEY_SPACE, _(KEY_1), _(KEY_QUOTE), _(KEY_3), _(KEY_4), _(KEY_5), _(KEY_7), KEY_QUOTE, - // ()*+,-./ - _(KEY_9), _(KEY_0), _(KEY_8), _(KEY_EQUAL), KEY_COMMA, KEY_MINUS, KEY_PERIOD, KEY_SLASH, - // 0..9 - 39, 30, 31, 32, 33, 34, 35, 36, 37, 38, - // :;<=>?@ - _(KEY_SEMICOLON), KEY_SEMICOLON, _(KEY_COMMA), KEY_EQUAL, _(KEY_PERIOD), _(KEY_SLASH), _(KEY_2), - // A..Z: for a in $(seq 0 25); do printf "$((a+132)),"; done - 132,133,134,135,136,137,138,139,140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157, - // [\]^_` - KEY_LEFT_BRACE, KEY_BACKSLASH, KEY_RIGHT_BRACE, _(KEY_6), _(KEY_MINUS), KEY_TILDE, - // a..z: for a in $(seq 0 25); do printf "$((a+4)),"; done - 4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29, - // {|}~ - _(KEY_LEFT_BRACE), _(KEY_BACKSLASH), _(KEY_RIGHT_BRACE), _(KEY_TILDE) -}; - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY){ - buf[0] = MOD; - buf[2] = KEY; - return buf; -} - -/** - * return buffer for sending symbol "ltr" with addition modificator mod - */ -uint8_t *press_key_mod(char ltr, uint8_t mod){ - uint8_t MOD = 0; - uint8_t KEY = 0; - if(ltr > 31){ - KEY = keycodes[ltr - 32]; - if(KEY & 0x80){ - MOD = MOD_SHIFT; - KEY &= 0x7f; - } - }else if (ltr == '\n') KEY = KEY_ENTER; - buf[0] = MOD | mod; - buf[2] = KEY; - return buf; -} diff --git a/Timelapse_keyboard/keycodes.h b/Timelapse_keyboard/keycodes.h deleted file mode 100644 index 98a2fa1..0000000 --- a/Timelapse_keyboard/keycodes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* - * keycodes.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __KEYKODES_H__ -#define __KEYKODES_H__ - -#include - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY); -#define release_key() set_key_buf(0,0) -uint8_t *press_key_mod(char key, uint8_t mod); -#define press_key(k) press_key_mod(k, 0) - -#define MOD_CTRL 0x01 -#define MOD_SHIFT 0x02 -#define MOD_ALT 0x04 -#define MOD_GUI 0x08 - -#define LEFT(mod) (mod) -#define RIGHT(mod) ((mod << 4)) - -#define KEY_A 4 -#define KEY_B 5 -#define KEY_C 6 -#define KEY_D 7 -#define KEY_E 8 -#define KEY_F 9 -#define KEY_G 10 -#define KEY_H 11 -#define KEY_I 12 -#define KEY_J 13 -#define KEY_K 14 -#define KEY_L 15 -#define KEY_M 16 -#define KEY_N 17 -#define KEY_O 18 -#define KEY_P 19 -#define KEY_Q 20 -#define KEY_R 21 -#define KEY_S 22 -#define KEY_T 23 -#define KEY_U 24 -#define KEY_V 25 -#define KEY_W 26 -#define KEY_X 27 -#define KEY_Y 28 -#define KEY_Z 29 -#define KEY_1 30 -#define KEY_2 31 -#define KEY_3 32 -#define KEY_4 33 -#define KEY_5 34 -#define KEY_6 35 -#define KEY_7 36 -#define KEY_8 37 -#define KEY_9 38 -#define KEY_0 39 -#define KEY_ENTER 40 -#define KEY_ESC 41 -#define KEY_BACKSPACE 42 -#define KEY_TAB 43 -#define KEY_SPACE 44 -#define KEY_MINUS 45 -#define KEY_EQUAL 46 -#define KEY_LEFT_BRACE 47 -#define KEY_RIGHT_BRACE 48 -#define KEY_BACKSLASH 49 -#define KEY_NUMBER 50 -#define KEY_SEMICOLON 51 -#define KEY_QUOTE 52 -#define KEY_TILDE 53 -#define KEY_COMMA 54 -#define KEY_PERIOD 55 -#define KEY_SLASH 56 -#define KEY_CAPS_LOCK 57 -#define KEY_F1 58 -#define KEY_F2 59 -#define KEY_F3 60 -#define KEY_F4 61 -#define KEY_F5 62 -#define KEY_F6 63 -#define KEY_F7 64 -#define KEY_F8 65 -#define KEY_F9 66 -#define KEY_F10 67 -#define KEY_F11 68 -#define KEY_F12 69 -#define KEY_PRINTSCREEN 70 -#define KEY_SCROLL_LOCK 71 -#define KEY_PAUSE 72 -#define KEY_INSERT 73 -#define KEY_HOME 74 -#define KEY_PAGE_UP 75 -#define KEY_DELETE 76 -#define KEY_END 77 -#define KEY_PAGE_DOWN 78 -#define KEY_RIGHT 79 -#define KEY_LEFT 80 -#define KEY_DOWN 81 -#define KEY_UP 82 -#define KEY_NUM_LOCK 83 -#define KEYPAD_SLASH 84 -#define KEYPAD_ASTERIX 85 -#define KEYPAD_MINUS 86 -#define KEYPAD_PLUS 87 -#define KEYPAD_ENTER 88 -#define KEYPAD_1 89 -#define KEYPAD_2 90 -#define KEYPAD_3 91 -#define KEYPAD_4 92 -#define KEYPAD_5 93 -#define KEYPAD_6 94 -#define KEYPAD_7 95 -#define KEYPAD_8 96 -#define KEYPAD_9 97 -#define KEYPAD_0 98 -#define KEYPAD_PERIOD 99 - -#endif // __KEYKODES_H__ diff --git a/Timelapse_keyboard/kicad/LEDs.cmp b/Timelapse_keyboard/kicad/LEDs.cmp deleted file mode 100644 index 436d68d..0000000 --- a/Timelapse_keyboard/kicad/LEDs.cmp +++ /dev/null @@ -1,94 +0,0 @@ -Cmp-Mod V01 Created by CvPcb (2013-feb-26)-stable date = Чт 10 Ñен 2015 12:17:33 - -BeginCmp -TimeStamp = /55F14513; -Reference = D1; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F14969; -Reference = D2; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F14976; -Reference = D3; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F14983; -Reference = D4; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F14990; -Reference = D5; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F1499D; -Reference = D6; -ValeurCmp = LED; -IdModule = LED-3MM; -EndCmp - -BeginCmp -TimeStamp = /55F149BB; -Reference = P1; -ValeurCmp = CONN_7; -IdModule = SIL-7; -EndCmp - -BeginCmp -TimeStamp = /55F14522; -Reference = R1; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -BeginCmp -TimeStamp = /55F1496F; -Reference = R2; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -BeginCmp -TimeStamp = /55F1497C; -Reference = R3; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -BeginCmp -TimeStamp = /55F14989; -Reference = R4; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -BeginCmp -TimeStamp = /55F14996; -Reference = R5; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -BeginCmp -TimeStamp = /55F149A3; -Reference = R6; -ValeurCmp = 100; -IdModule = SM0603; -EndCmp - -EndListe diff --git a/Timelapse_keyboard/kicad/LEDs.net b/Timelapse_keyboard/kicad/LEDs.net deleted file mode 100644 index 23fc991..0000000 --- a/Timelapse_keyboard/kicad/LEDs.net +++ /dev/null @@ -1,174 +0,0 @@ -(export (version D) - (design - (source /home/eddy/Docs/SAO/ELECTRONICS/STM32/c8t6/Timelapse_keyboard/kicad/LEDs.sch) - (date "Чт 10 Ñен 2015 12:15:21") - (tool "eeschema (2013-feb-26)-stable")) - (components - (comp (ref D1) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14513)) - (comp (ref R1) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14522)) - (comp (ref D2) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14969)) - (comp (ref R2) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F1496F)) - (comp (ref D3) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14976)) - (comp (ref R3) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F1497C)) - (comp (ref D4) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14983)) - (comp (ref R4) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14989)) - (comp (ref D5) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14990)) - (comp (ref R5) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F14996)) - (comp (ref D6) - (value LED) - (libsource (lib device) (part LED)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F1499D)) - (comp (ref R6) - (value 100) - (footprint SM0603) - (libsource (lib device) (part R)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F149A3)) - (comp (ref P1) - (value CONN_7) - (libsource (lib conn) (part CONN_7)) - (sheetpath (names /) (tstamps /)) - (tstamp 55F149BB))) - (libparts - (libpart (lib device) (part LED) - (footprints - (fp LED-3MM) - (fp LED-5MM) - (fp LED-10MM) - (fp LED-0603) - (fp LED-0805) - (fp LED-1206) - (fp LEDV)) - (fields - (field (name Reference) D) - (field (name Value) LED) - (field (name Footprint) ~) - (field (name Datasheet) ~)) - (pins - (pin (num 1) (name A) (type passive)) - (pin (num 2) (name K) (type passive)))) - (libpart (lib device) (part R) - (description Resistance) - (footprints - (fp R?) - (fp SM0603) - (fp SM0805) - (fp R?-*) - (fp SM1206)) - (fields - (field (name Reference) R) - (field (name Value) R) - (field (name Footprint) ~) - (field (name Datasheet) ~)) - (pins - (pin (num 1) (name ~) (type passive)) - (pin (num 2) (name ~) (type passive)))) - (libpart (lib conn) (part CONN_7) - (description "Symbole general pour connexions") - (fields - (field (name Reference) P) - (field (name Value) CONN_7)) - (pins - (pin (num 1) (name P1) (type passive)) - (pin (num 2) (name P2) (type passive)) - (pin (num 3) (name P3) (type passive)) - (pin (num 4) (name P4) (type passive)) - (pin (num 5) (name P5) (type passive)) - (pin (num 6) (name P6) (type passive)) - (pin (num 7) (name P7) (type passive))))) - (libraries - (library (logical device) - (uri /usr/share/kicad/library/device.lib)) - (library (logical conn) - (uri /usr/share/kicad/library/conn.lib))) - (nets - (net (code 1) (name /G2) - (node (ref D6) (pin 2)) - (node (ref P1) (pin 6))) - (net (code 2) (name /R2) - (node (ref P1) (pin 4)) - (node (ref D4) (pin 2))) - (net (code 3) (name /R1) - (node (ref D3) (pin 2)) - (node (ref P1) (pin 3))) - (net (code 4) (name /Y2) - (node (ref D2) (pin 2)) - (node (ref P1) (pin 2))) - (net (code 5) (name /Y1) - (node (ref D1) (pin 2)) - (node (ref P1) (pin 1))) - (net (code 6) (name /G1) - (node (ref D5) (pin 2)) - (node (ref P1) (pin 5))) - (net (code 7) (name "") - (node (ref D2) (pin 1)) - (node (ref R2) (pin 2))) - (net (code 8) (name "") - (node (ref D3) (pin 1)) - (node (ref R3) (pin 2))) - (net (code 9) (name /+3.3V) - (node (ref P1) (pin 7)) - (node (ref R1) (pin 1)) - (node (ref R6) (pin 1)) - (node (ref R5) (pin 1)) - (node (ref R2) (pin 1)) - (node (ref R3) (pin 1)) - (node (ref R4) (pin 1))) - (net (code 10) (name "") - (node (ref D1) (pin 1)) - (node (ref R1) (pin 2))) - (net (code 11) (name "") - (node (ref D4) (pin 1)) - (node (ref R4) (pin 2))) - (net (code 12) (name "") - (node (ref D5) (pin 1)) - (node (ref R5) (pin 2))) - (net (code 13) (name "") - (node (ref D6) (pin 1)) - (node (ref R6) (pin 2))))) \ No newline at end of file diff --git a/Timelapse_keyboard/kicad/LEDs.sch b/Timelapse_keyboard/kicad/LEDs.sch deleted file mode 100644 index a31bb2e..0000000 --- a/Timelapse_keyboard/kicad/LEDs.sch +++ /dev/null @@ -1,256 +0,0 @@ -EESchema Schematic File Version 2 date Чт 10 Ñен 2015 12:15:08 -LIBS:power -LIBS:device -LIBS:transistors -LIBS:conn -LIBS:linear -LIBS:regul -LIBS:74xx -LIBS:cmos4000 -LIBS:adc-dac -LIBS:memory -LIBS:xilinx -LIBS:special -LIBS:microcontrollers -LIBS:dsp -LIBS:microchip -LIBS:analog_switches -LIBS:motorola -LIBS:texas -LIBS:intel -LIBS:audio -LIBS:interface -LIBS:digital-audio -LIBS:philips -LIBS:display -LIBS:cypress -LIBS:siliconi -LIBS:opto -LIBS:atmel -LIBS:contrib -LIBS:valves -EELAYER 27 0 -EELAYER END -$Descr A4 11693 8268 -encoding utf-8 -Sheet 1 1 -Title "" -Date "10 sep 2015" -Rev "" -Comp "" -Comment1 "" -Comment2 "" -Comment3 "" -Comment4 "" -$EndDescr -$Comp -L LED D1 -U 1 1 55F14513 -P 2350 1300 -F 0 "D1" H 2350 1400 50 0000 C CNN -F 1 "LED" H 2350 1200 50 0000 C CNN -F 2 "~" H 2350 1300 60 0000 C CNN -F 3 "~" H 2350 1300 60 0000 C CNN - 1 2350 1300 - 1 0 0 -1 -$EndComp -$Comp -L R R1 -U 1 1 55F14522 -P 1850 1300 -F 0 "R1" V 1930 1300 40 0000 C CNN -F 1 "100" V 1857 1301 40 0000 C CNN -F 2 "SM0603" V 1780 1300 30 0001 C CNN -F 3 "~" H 1850 1300 30 0000 C CNN - 1 1850 1300 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 1300 2150 1300 -$Comp -L LED D2 -U 1 1 55F14969 -P 2350 1650 -F 0 "D2" H 2350 1750 50 0000 C CNN -F 1 "LED" H 2350 1550 50 0000 C CNN -F 2 "~" H 2350 1650 60 0000 C CNN -F 3 "~" H 2350 1650 60 0000 C CNN - 1 2350 1650 - 1 0 0 -1 -$EndComp -$Comp -L R R2 -U 1 1 55F1496F -P 1850 1650 -F 0 "R2" V 1930 1650 40 0000 C CNN -F 1 "100" V 1857 1651 40 0000 C CNN -F 2 "SM0603" V 1780 1650 30 0001 C CNN -F 3 "~" H 1850 1650 30 0000 C CNN - 1 1850 1650 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 1650 2150 1650 -$Comp -L LED D3 -U 1 1 55F14976 -P 2350 2050 -F 0 "D3" H 2350 2150 50 0000 C CNN -F 1 "LED" H 2350 1950 50 0000 C CNN -F 2 "~" H 2350 2050 60 0000 C CNN -F 3 "~" H 2350 2050 60 0000 C CNN - 1 2350 2050 - 1 0 0 -1 -$EndComp -$Comp -L R R3 -U 1 1 55F1497C -P 1850 2050 -F 0 "R3" V 1930 2050 40 0000 C CNN -F 1 "100" V 1857 2051 40 0000 C CNN -F 2 "SM0603" V 1780 2050 30 0001 C CNN -F 3 "~" H 1850 2050 30 0000 C CNN - 1 1850 2050 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 2050 2150 2050 -$Comp -L LED D4 -U 1 1 55F14983 -P 2350 2400 -F 0 "D4" H 2350 2500 50 0000 C CNN -F 1 "LED" H 2350 2300 50 0000 C CNN -F 2 "~" H 2350 2400 60 0000 C CNN -F 3 "~" H 2350 2400 60 0000 C CNN - 1 2350 2400 - 1 0 0 -1 -$EndComp -$Comp -L R R4 -U 1 1 55F14989 -P 1850 2400 -F 0 "R4" V 1930 2400 40 0000 C CNN -F 1 "100" V 1857 2401 40 0000 C CNN -F 2 "SM0603" V 1780 2400 30 0001 C CNN -F 3 "~" H 1850 2400 30 0000 C CNN - 1 1850 2400 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 2400 2150 2400 -$Comp -L LED D5 -U 1 1 55F14990 -P 2350 2750 -F 0 "D5" H 2350 2850 50 0000 C CNN -F 1 "LED" H 2350 2650 50 0000 C CNN -F 2 "~" H 2350 2750 60 0000 C CNN -F 3 "~" H 2350 2750 60 0000 C CNN - 1 2350 2750 - 1 0 0 -1 -$EndComp -$Comp -L R R5 -U 1 1 55F14996 -P 1850 2750 -F 0 "R5" V 1930 2750 40 0000 C CNN -F 1 "100" V 1857 2751 40 0000 C CNN -F 2 "SM0603" V 1780 2750 30 0001 C CNN -F 3 "~" H 1850 2750 30 0000 C CNN - 1 1850 2750 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 2750 2150 2750 -$Comp -L LED D6 -U 1 1 55F1499D -P 2350 3100 -F 0 "D6" H 2350 3200 50 0000 C CNN -F 1 "LED" H 2350 3000 50 0000 C CNN -F 2 "~" H 2350 3100 60 0000 C CNN -F 3 "~" H 2350 3100 60 0000 C CNN - 1 2350 3100 - 1 0 0 -1 -$EndComp -$Comp -L R R6 -U 1 1 55F149A3 -P 1850 3100 -F 0 "R6" V 1930 3100 40 0000 C CNN -F 1 "100" V 1857 3101 40 0000 C CNN -F 2 "SM0603" V 1780 3100 30 0001 C CNN -F 3 "~" H 1850 3100 30 0000 C CNN - 1 1850 3100 - 0 -1 -1 0 -$EndComp -Wire Wire Line - 2100 3100 2150 3100 -Wire Wire Line - 1600 1300 1600 3300 -Connection ~ 1600 1650 -Connection ~ 1600 2050 -Connection ~ 1600 2400 -Connection ~ 1600 2750 -$Comp -L CONN_7 P1 -U 1 1 55F149BB -P 3350 1600 -F 0 "P1" V 3320 1600 60 0000 C CNN -F 1 "CONN_7" V 3420 1600 60 0000 C CNN -F 2 "" H 3350 1600 60 0000 C CNN -F 3 "" H 3350 1600 60 0000 C CNN - 1 3350 1600 - 1 0 0 -1 -$EndComp -Wire Wire Line - 3000 1300 2550 1300 -Wire Wire Line - 2550 1650 2550 1400 -Wire Wire Line - 2550 1400 3000 1400 -Wire Wire Line - 2550 2050 2600 2050 -Wire Wire Line - 2600 2050 2600 1500 -Wire Wire Line - 2600 1500 3000 1500 -Wire Wire Line - 2550 2400 2650 2400 -Wire Wire Line - 2650 2400 2650 1600 -Wire Wire Line - 2650 1600 3000 1600 -Wire Wire Line - 3000 1700 2700 1700 -Wire Wire Line - 2700 1700 2700 2750 -Wire Wire Line - 2700 2750 2550 2750 -Wire Wire Line - 2550 3100 2750 3100 -Wire Wire Line - 2750 3100 2750 1800 -Wire Wire Line - 2750 1800 3000 1800 -Wire Wire Line - 1600 3300 3000 3300 -Wire Wire Line - 3000 3300 3000 1900 -Connection ~ 1600 3100 -Text Label 3000 2150 0 60 ~ 0 -+3.3V -Text Label 2850 1300 2 60 ~ 0 -Y1 -Text Label 2850 1400 2 60 ~ 0 -Y2 -Text Label 2850 1500 2 60 ~ 0 -R1 -Text Label 2850 1600 2 60 ~ 0 -R2 -Text Label 2850 1700 2 60 ~ 0 -G1 -Text Label 2850 1800 2 60 ~ 0 -G2 -$EndSCHEMATC diff --git a/Timelapse_keyboard/kicad/diff_schematics-B_Cu.svg b/Timelapse_keyboard/kicad/diff_schematics-B_Cu.svg deleted file mode 100644 index 81659a4..0000000 --- a/Timelapse_keyboard/kicad/diff_schematics-B_Cu.svg +++ /dev/null @@ -1,9212 +0,0 @@ - - - - - - image/svg+xml - - SVG Picture created as diff_schematics-B_Cu.svg date 2015/09/10 12:43:34 - - - - - - - - SVG Picture created as diff_schematics-B_Cu.svg date 2015/09/10 12:43:34 - Picture generated by PCBNEW - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/Timelapse_keyboard/kicad/diff_schematics.kicad_pcb b/Timelapse_keyboard/kicad/diff_schematics.kicad_pcb deleted file mode 100644 index 6c349dc..0000000 --- a/Timelapse_keyboard/kicad/diff_schematics.kicad_pcb +++ /dev/null @@ -1,847 +0,0 @@ -(kicad_pcb (version 3) (host pcbnew "(2013-feb-26)-stable") - - (general - (links 18) - (no_connects 0) - (area 55.730227 47.18873 83.841401 74.414001) - (thickness 1.6) - (drawings 20) - (tracks 75) - (zones 0) - (modules 17) - (nets 14) - ) - - (page A3) - (layers - (15 F.Cu signal) - (0 B.Cu signal) - (16 B.Adhes user) - (17 F.Adhes user) - (18 B.Paste user) - (19 F.Paste user) - (20 B.SilkS user) - (21 F.SilkS user) - (22 B.Mask user) - (23 F.Mask user) - (24 Dwgs.User user) - (25 Cmts.User user) - (26 Eco1.User user) - (27 Eco2.User user) - (28 Edge.Cuts user) - ) - - (setup - (last_trace_width 0.5) - (trace_clearance 0.254) - (zone_clearance 0.508) - (zone_45_only no) - (trace_min 0.5) - (segment_width 0.2) - (edge_width 0.15) - (via_size 0.889) - (via_drill 0.635) - (via_min_size 0.889) - (via_min_drill 0.508) - (uvia_size 0.508) - (uvia_drill 0.127) - (uvias_allowed no) - (uvia_min_size 0.508) - (uvia_min_drill 0.127) - (pcb_text_width 0.3) - (pcb_text_size 1 1) - (mod_edge_width 0.15) - (mod_text_size 1 1) - (mod_text_width 0.15) - (pad_size 1 1) - (pad_drill 0.6) - (pad_to_mask_clearance 0) - (aux_axis_origin 0 0) - (visible_elements FFFFFFBF) - (pcbplotparams - (layerselection 3178497) - (usegerberextensions true) - (excludeedgelayer true) - (linewidth 152400) - (plotframeref false) - (viasonmask false) - (mode 1) - (useauxorigin false) - (hpglpennumber 1) - (hpglpenspeed 20) - (hpglpendiameter 15) - (hpglpenoverlay 2) - (psnegative false) - (psa4output false) - (plotreference true) - (plotvalue true) - (plotothertext true) - (plotinvisibletext false) - (padsonsilk false) - (subtractmaskfromsilk false) - (outputformat 1) - (mirror false) - (drillshape 1) - (scaleselection 1) - (outputdirectory "")) - ) - - (net 0 "") - (net 1 /+3.3V) - (net 2 /G1) - (net 3 /G2) - (net 4 /R1) - (net 5 /R2) - (net 6 /Y1) - (net 7 /Y2) - (net 8 N-0000010) - (net 9 N-0000011) - (net 10 N-0000012) - (net 11 N-0000013) - (net 12 N-000007) - (net 13 N-000008) - - (net_class Default "This is the default net class." - (clearance 0.254) - (trace_width 0.5) - (via_dia 0.889) - (via_drill 0.635) - (uvia_dia 0.508) - (uvia_drill 0.127) - (add_net "") - (add_net /G1) - (add_net /G2) - (add_net /R1) - (add_net /R2) - (add_net /Y1) - (add_net /Y2) - (add_net N-0000010) - (add_net N-0000011) - (add_net N-0000012) - (add_net N-0000013) - (add_net N-000007) - (add_net N-000008) - ) - - (net_class WIDE "" - (clearance 0.254) - (trace_width 1) - (via_dia 0.889) - (via_drill 0.635) - (uvia_dia 0.508) - (uvia_drill 0.127) - (add_net /+3.3V) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14ADA) - (at 57.4 56.6) - (path /55F14522) - (attr smd) - (fp_text reference R1 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 8 N-0000010) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14AE4) - (at 57.4 66.6) - (path /55F1496F) - (attr smd) - (fp_text reference R2 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 12 N-000007) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14AEE) - (at 67.8 56.6) - (path /55F1497C) - (attr smd) - (fp_text reference R3 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 13 N-000008) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14AF8) - (at 67.8 66.6) - (path /55F14989) - (attr smd) - (fp_text reference R4 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 9 N-0000011) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14B02) - (at 77.3 56.6) - (path /55F14996) - (attr smd) - (fp_text reference R5 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 10 N-0000012) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SM0603 (layer B.Cu) (tedit 4E43A3D1) (tstamp 55F14B0C) - (at 77.3 66.6) - (path /55F149A3) - (attr smd) - (fp_text reference R6 (at 0 0) (layer B.SilkS) - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_text value 100 (at 0 0) (layer B.SilkS) hide - (effects (font (size 0.508 0.4572) (thickness 0.1143)) (justify mirror)) - ) - (fp_line (start -1.143 0.635) (end 1.143 0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 0.635) (end 1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start 1.143 -0.635) (end -1.143 -0.635) (layer B.SilkS) (width 0.127)) - (fp_line (start -1.143 -0.635) (end -1.143 0.635) (layer B.SilkS) (width 0.127)) - (pad 1 smd rect (at -0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 1 /+3.3V) - ) - (pad 2 smd rect (at 0.762 0) (size 0.635 1.143) - (layers B.Cu B.Paste B.Mask) - (net 11 N-0000013) - ) - (model smd\resistors\R0603.wrl - (at (xyz 0 0 0.001)) - (scale (xyz 0.5 0.5 0.5)) - (rotate (xyz 0 0 0)) - ) - ) - - (module SIL-7 (layer F.Cu) (tedit 200000) (tstamp 55F14B1E) - (at 70.5 51) - (descr "Connecteur 7 pins") - (tags "CONN DEV") - (path /55F149BB) - (fp_text reference P1 (at 0 -2.54) (layer F.SilkS) - (effects (font (size 1.72974 1.08712) (thickness 0.3048))) - ) - (fp_text value CONN_7 (at 0 -2.54) (layer F.SilkS) hide - (effects (font (size 1.524 1.016) (thickness 0.3048))) - ) - (fp_line (start -8.89 -1.27) (end -8.89 -1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start -8.89 -1.27) (end 8.89 -1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start 8.89 -1.27) (end 8.89 1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start 8.89 1.27) (end -8.89 1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start -8.89 1.27) (end -8.89 -1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start -6.35 1.27) (end -6.35 1.27) (layer F.SilkS) (width 0.3048)) - (fp_line (start -6.35 1.27) (end -6.35 -1.27) (layer F.SilkS) (width 0.3048)) - (pad 1 thru_hole rect (at -7.62 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.Mask F.SilkS) - (net 6 /Y1) - ) - (pad 2 thru_hole circle (at -5.08 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 7 /Y2) - ) - (pad 3 thru_hole circle (at -2.54 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 4 /R1) - ) - (pad 4 thru_hole circle (at 0 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 5 /R2) - ) - (pad 5 thru_hole circle (at 2.54 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 2 /G1) - ) - (pad 6 thru_hole circle (at 5.08 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 3 /G2) - ) - (pad 7 thru_hole circle (at 7.62 0) (size 1.397 1.397) (drill 0.8128) - (layers *.Cu *.SilkS *.Mask) - (net 1 /+3.3V) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14B37) - (at 60 60) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F14513) - (fp_text reference D1 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 8 N-0000010) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 6 /Y1) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14B50) - (at 60 70) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F14969) - (fp_text reference D2 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 12 N-000007) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 7 /Y2) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14B69) - (at 70 60) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F14976) - (fp_text reference D3 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 13 N-000008) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 4 /R1) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14B82) - (at 70 70) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F14983) - (fp_text reference D4 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 9 N-0000011) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 5 /R2) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14B9B) - (at 80 60) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F14990) - (fp_text reference D5 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 10 N-0000012) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 2 /G1) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module LED-3MM (layer F.Cu) (tedit 49BFA23B) (tstamp 55F14BB4) - (at 80 70) - (descr "LED 3mm - Lead pitch 100mil (2,54mm)") - (tags "LED led 3mm 3MM 100mil 2,54mm") - (path /55F1499D) - (fp_text reference D6 (at 1.778 -2.794) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_text value LED (at 0 2.54) (layer F.SilkS) - (effects (font (size 0.762 0.762) (thickness 0.0889))) - ) - (fp_line (start 1.8288 1.27) (end 1.8288 -1.27) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.27 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.88392 1.01092) (angle 41.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.4097 -0.9906) (angle 40.6) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.778 0) (angle 39.8) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -1.524) (angle 54.4) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.9652 -0.9144) (angle 53.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.45542 0.93472) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 1.524) (angle 52.1) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.381 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end -0.762 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.889 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 1.27 0) (angle 90) (layer F.SilkS) (width 0.1524)) - (fp_arc (start 0.254 0) (end 0.254 -2.032) (angle 50.1) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.5367 -0.95504) (angle 61.9) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 1.8034 1.31064) (angle 49.7) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end 0.254 2.032) (angle 60.2) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.778 0) (angle 28.3) (layer F.SilkS) (width 0.254)) - (fp_arc (start 0.254 0) (end -1.47574 1.06426) (angle 31.6) (layer F.SilkS) (width 0.254)) - (pad 1 thru_hole circle (at -1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 11 N-0000013) - ) - (pad 2 thru_hole circle (at 1.27 0) (size 1.6764 1.6764) (drill 0.8128) - (layers *.Cu F.Paste F.SilkS F.Mask) - (net 3 /G2) - ) - (model discret/leds/led3_vertical_verde.wrl - (at (xyz 0 0 0)) - (scale (xyz 1 1 1)) - (rotate (xyz 0 0 0)) - ) - ) - - (module hole_3mm (layer F.Cu) (tedit 547491FA) (tstamp 55F15D5E) - (at 90 65) - (fp_text reference hole_3mm (at 0 -2.54) (layer F.SilkS) hide - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_text value Val** (at 0 3.175) (layer F.SilkS) - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_line (start 0 2.5) (end 0 1.5) (layer F.SilkS) (width 0.3)) - (fp_line (start -2.5 0) (end -1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 2.5 0) (end 1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 0 -1.5) (end 0 -2.5) (layer F.SilkS) (width 0.3)) - (fp_circle (center 0 0) (end 2.5 0) (layer F.SilkS) (width 0.3)) - (pad "" thru_hole circle (at 0 0) (size 3 3) (drill 3) - (layers *.Cu F.SilkS) - ) - ) - - (module hole_3mm (layer F.Cu) (tedit 547491FA) (tstamp 55F15D75) - (at 50 65) - (fp_text reference hole_3mm (at 0 -2.54) (layer F.SilkS) hide - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_text value Val** (at 0 3.175) (layer F.SilkS) - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_line (start 0 2.5) (end 0 1.5) (layer F.SilkS) (width 0.3)) - (fp_line (start -2.5 0) (end -1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 2.5 0) (end 1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 0 -1.5) (end 0 -2.5) (layer F.SilkS) (width 0.3)) - (fp_circle (center 0 0) (end 2.5 0) (layer F.SilkS) (width 0.3)) - (pad "" thru_hole circle (at 0 0) (size 3 3) (drill 3) - (layers *.Cu F.SilkS) - ) - ) - - (module hole_3mm (layer F.Cu) (tedit 547491FA) (tstamp 55F15D88) - (at 50 50) - (fp_text reference hole_3mm (at 0 -2.54) (layer F.SilkS) hide - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_text value Val** (at 0 3.175) (layer F.SilkS) - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_line (start 0 2.5) (end 0 1.5) (layer F.SilkS) (width 0.3)) - (fp_line (start -2.5 0) (end -1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 2.5 0) (end 1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 0 -1.5) (end 0 -2.5) (layer F.SilkS) (width 0.3)) - (fp_circle (center 0 0) (end 2.5 0) (layer F.SilkS) (width 0.3)) - (pad "" thru_hole circle (at 0 0) (size 3 3) (drill 3) - (layers *.Cu F.SilkS) - ) - ) - - (module hole_3mm (layer F.Cu) (tedit 547491FA) (tstamp 55F15D9B) - (at 90 50) - (fp_text reference hole_3mm (at 0 -2.54) (layer F.SilkS) hide - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_text value Val** (at 0 3.175) (layer F.SilkS) - (effects (font (size 1.5 1.5) (thickness 0.3))) - ) - (fp_line (start 0 2.5) (end 0 1.5) (layer F.SilkS) (width 0.3)) - (fp_line (start -2.5 0) (end -1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 2.5 0) (end 1.5 0) (layer F.SilkS) (width 0.3)) - (fp_line (start 0 -1.5) (end 0 -2.5) (layer F.SilkS) (width 0.3)) - (fp_circle (center 0 0) (end 2.5 0) (layer F.SilkS) (width 0.3)) - (pad "" thru_hole circle (at 0 0) (size 3 3) (drill 3) - (layers *.Cu F.SilkS) - ) - ) - - (dimension 35 (width 0.25) (layer Dwgs.User) - (gr_text "35.000 mm" (at 39.000001 62.5 270) (layer Dwgs.User) - (effects (font (size 1 1) (thickness 0.25))) - ) - (feature1 (pts (xy 45 80) (xy 38.000001 80))) - (feature2 (pts (xy 45 45) (xy 38.000001 45))) - (crossbar (pts (xy 40.000001 45) (xy 40.000001 80))) - (arrow1a (pts (xy 40.000001 80) (xy 39.413581 78.873497))) - (arrow1b (pts (xy 40.000001 80) (xy 40.586421 78.873497))) - (arrow2a (pts (xy 40.000001 45) (xy 39.413581 46.126503))) - (arrow2b (pts (xy 40.000001 45) (xy 40.586421 46.126503))) - ) - (dimension 50 (width 0.25) (layer Dwgs.User) - (gr_text "50.000 mm" (at 70 39.000001) (layer Dwgs.User) - (effects (font (size 1 1) (thickness 0.25))) - ) - (feature1 (pts (xy 95 45) (xy 95 38.000001))) - (feature2 (pts (xy 45 45) (xy 45 38.000001))) - (crossbar (pts (xy 45 40.000001) (xy 95 40.000001))) - (arrow1a (pts (xy 95 40.000001) (xy 93.873497 40.586421))) - (arrow1b (pts (xy 95 40.000001) (xy 93.873497 39.413581))) - (arrow2a (pts (xy 45 40.000001) (xy 46.126503 40.586421))) - (arrow2b (pts (xy 45 40.000001) (xy 46.126503 39.413581))) - ) - (gr_line (start 45 80) (end 45 45) (angle 90) (layer Edge.Cuts) (width 0.15)) - (gr_line (start 95 80) (end 45 80) (angle 90) (layer Edge.Cuts) (width 0.15)) - (gr_line (start 95 45) (end 95 80) (angle 90) (layer Edge.Cuts) (width 0.15)) - (gr_line (start 45 45) (end 95 45) (angle 90) (layer Edge.Cuts) (width 0.15)) - (gr_text "Timelapse tool LEDs board" (at 70.358 76.327) (layer B.Cu) - (effects (font (size 2 2) (thickness 0.3)) (justify mirror)) - ) - (gr_text + (at 58.039 71.882) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text + (at 58.166 61.976) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text + (at 68.453 61.849) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text + (at 68.453 71.882) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text + (at 78.359 72.009) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text + (at 78.359 62.103) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text +3.3V (at 82.042 51.181) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text G2 (at 80.391 65.659) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text G1 (at 80.391 63.627) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text R1 (at 70.358 63.627) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text R2 (at 70.485 65.659) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text Y2 (at 60.325 65.532) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - (gr_text Y1 (at 60.325 63.5) (layer B.Cu) - (effects (font (size 1 1) (thickness 0.25)) (justify mirror)) - ) - - (segment (start 66.929 73.914) (end 66.929 66.709) (width 1) (layer B.Cu) (net 1)) - (segment (start 66.929 66.709) (end 67.038 66.6) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EC4)) - (segment (start 67.038 66.6) (end 67.038 56.6) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EC5)) - (segment (start 78.12 51) (end 78.12 49.418) (width 1) (layer B.Cu) (net 1)) - (segment (start 78.12 49.418) (end 77.216 48.514) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EB6)) - (segment (start 77.216 48.514) (end 60.071 48.514) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EB7)) - (segment (start 60.071 48.514) (end 56.638 51.947) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EB8)) - (segment (start 56.638 51.947) (end 56.638 66.6) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EB9)) - (segment (start 56.638 66.6) (end 56.638 72.767) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBA)) - (segment (start 56.638 72.767) (end 57.785 73.914) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBB)) - (segment (start 57.785 73.914) (end 66.929 73.914) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBC)) - (segment (start 66.929 73.914) (end 74.295 73.914) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EC2)) - (segment (start 74.295 73.914) (end 76.538 71.671) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBD)) - (segment (start 76.538 71.671) (end 76.538 66.6) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBE)) - (segment (start 76.538 66.6) (end 76.538 56.6) (width 1) (layer B.Cu) (net 1) (tstamp 55F14EBF)) - (segment (start 56.638 56.6) (end 56.638 51.947) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 77.216 48.514) (end 78.12 49.418) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14EAB)) - (segment (start 60.071 48.514) (end 77.216 48.514) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14EA9)) - (segment (start 56.638 51.947) (end 60.071 48.514) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14EA7)) - (segment (start 67.038 66.6) (end 67.038 73.914) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 56.638 66.6) (end 56.638 72.767) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 56.638 72.767) (end 57.785 73.914) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14E9C)) - (segment (start 57.785 73.914) (end 67.038 73.914) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14E9D)) - (segment (start 76.538 71.544) (end 76.538 66.6) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14E9F)) - (segment (start 67.038 73.914) (end 74.168 73.914) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14EA5)) - (segment (start 74.168 73.914) (end 76.538 71.544) (width 0.5) (layer B.Cu) (net 1) (tstamp 55F14E9E)) - (segment (start 56.638 66.6) (end 56.638 56.6) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 67.038 66.6) (end 67.038 56.6) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 76.538 66.6) (end 76.538 56.6) (width 0.5) (layer B.Cu) (net 1)) - (segment (start 73.04 51) (end 73.04 52.0596) (width 0.5) (layer B.Cu) (net 2)) - (segment (start 82.3468 58.9232) (end 81.27 60) (width 0.5) (layer B.Cu) (net 2) (tstamp 55F14E12)) - (segment (start 82.3468 55.4228) (end 82.3468 58.9232) (width 0.5) (layer B.Cu) (net 2) (tstamp 55F14E11)) - (segment (start 81.1022 54.1782) (end 82.3468 55.4228) (width 0.5) (layer B.Cu) (net 2) (tstamp 55F14E10)) - (segment (start 75.1586 54.1782) (end 81.1022 54.1782) (width 0.5) (layer B.Cu) (net 2) (tstamp 55F14E0F)) - (segment (start 73.04 52.0596) (end 75.1586 54.1782) (width 0.5) (layer B.Cu) (net 2) (tstamp 55F14E0E)) - (segment (start 75.58 51) (end 75.58 52.2628) (width 0.5) (layer B.Cu) (net 3)) - (segment (start 83.5914 67.6786) (end 81.27 70) (width 0.5) (layer B.Cu) (net 3) (tstamp 55F14E1A)) - (segment (start 83.5914 55.0164) (end 83.5914 67.6786) (width 0.5) (layer B.Cu) (net 3) (tstamp 55F14E19)) - (segment (start 81.6356 53.0606) (end 83.5914 55.0164) (width 0.5) (layer B.Cu) (net 3) (tstamp 55F14E17)) - (segment (start 76.3778 53.0606) (end 81.6356 53.0606) (width 0.5) (layer B.Cu) (net 3) (tstamp 55F14E16)) - (segment (start 75.58 52.2628) (end 76.3778 53.0606) (width 0.5) (layer B.Cu) (net 3) (tstamp 55F14E15)) - (segment (start 71.27 60) (end 71.27 59.9464) (width 0.5) (layer B.Cu) (net 4)) - (segment (start 67.96 52.3136) (end 67.96 51) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF9)) - (segment (start 69.8754 54.229) (end 67.96 52.3136) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF8)) - (segment (start 71.0184 54.229) (end 69.8754 54.229) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF7)) - (segment (start 72.0344 55.245) (end 71.0184 54.229) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF6)) - (segment (start 72.0344 59.182) (end 72.0344 55.245) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF5)) - (segment (start 71.27 59.9464) (end 72.0344 59.182) (width 0.5) (layer B.Cu) (net 4) (tstamp 55F14DF4)) - (segment (start 71.27 70) (end 72.1638 70) (width 0.5) (layer B.Cu) (net 5)) - (segment (start 70.5 52.1358) (end 70.5 51) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DF1)) - (segment (start 71.7804 53.4162) (end 70.5 52.1358) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DF0)) - (segment (start 72.263 53.4162) (end 71.7804 53.4162) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DEF)) - (segment (start 73.7616 54.9148) (end 72.263 53.4162) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DEE)) - (segment (start 73.7616 68.4022) (end 73.7616 54.9148) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DED)) - (segment (start 72.1638 70) (end 73.7616 68.4022) (width 0.5) (layer B.Cu) (net 5) (tstamp 55F14DEC)) - (segment (start 61.27 60) (end 61.9454 60) (width 0.5) (layer B.Cu) (net 6)) - (segment (start 61.9454 60) (end 62.88 59.0654) (width 0.5) (layer B.Cu) (net 6) (tstamp 55F14DCD)) - (segment (start 62.88 59.0654) (end 62.88 51) (width 0.5) (layer B.Cu) (net 6) (tstamp 55F14DCE)) - (segment (start 62.88 59.0654) (end 62.88 51) (width 0.254) (layer B.Cu) (net 6) (tstamp 55F14DB4)) - (segment (start 61.9454 60) (end 62.88 59.0654) (width 0.254) (layer B.Cu) (net 6) (tstamp 55F14DB3)) - (segment (start 61.27 70) (end 61.6736 70) (width 0.5) (layer B.Cu) (net 7)) - (segment (start 65.42 66.2536) (end 65.42 51) (width 0.5) (layer B.Cu) (net 7) (tstamp 55F14DDE)) - (segment (start 61.6736 70) (end 65.42 66.2536) (width 0.5) (layer B.Cu) (net 7) (tstamp 55F14DDD)) - (segment (start 58.73 60) (end 58.73 57.168) (width 0.5) (layer B.Cu) (net 8)) - (segment (start 58.73 57.168) (end 58.162 56.6) (width 0.5) (layer B.Cu) (net 8) (tstamp 55F14E8B)) - (segment (start 68.73 70) (end 68.73 66.768) (width 0.5) (layer B.Cu) (net 9)) - (segment (start 68.73 66.768) (end 68.562 66.6) (width 0.5) (layer B.Cu) (net 9) (tstamp 55F14E93)) - (segment (start 78.73 60) (end 78.73 57.268) (width 0.5) (layer B.Cu) (net 10)) - (segment (start 78.73 57.268) (end 78.062 56.6) (width 0.5) (layer B.Cu) (net 10) (tstamp 55F14E78)) - (segment (start 78.73 70) (end 78.73 67.268) (width 0.5) (layer B.Cu) (net 11)) - (segment (start 78.73 67.268) (end 78.062 66.6) (width 0.5) (layer B.Cu) (net 11) (tstamp 55F14E7B)) - (segment (start 58.73 70) (end 58.73 67.168) (width 0.5) (layer B.Cu) (net 12)) - (segment (start 58.73 67.168) (end 58.162 66.6) (width 0.5) (layer B.Cu) (net 12) (tstamp 55F14E88)) - (segment (start 68.73 60) (end 68.73 56.768) (width 0.5) (layer B.Cu) (net 13)) - (segment (start 68.73 56.768) (end 68.562 56.6) (width 0.5) (layer B.Cu) (net 13) (tstamp 55F14E84)) - -) diff --git a/Timelapse_keyboard/kicad/diff_schematics.pro b/Timelapse_keyboard/kicad/diff_schematics.pro deleted file mode 100644 index 2275d70..0000000 --- a/Timelapse_keyboard/kicad/diff_schematics.pro +++ /dev/null @@ -1,81 +0,0 @@ -update=Чт 10 Ñен 2015 12:39:36 -version=1 -last_client=pcbnew -[cvpcb] -version=1 -NetIExt=net -[cvpcb/libraries] -EquName1=devcms -[eeschema] -version=1 -LibDir= -NetFmtName= -RptD_X=0 -RptD_Y=100 -RptLab=1 -LabSize=60 -[eeschema/libraries] -LibName1=power -LibName2=device -LibName3=transistors -LibName4=conn -LibName5=linear -LibName6=regul -LibName7=74xx -LibName8=cmos4000 -LibName9=adc-dac -LibName10=memory -LibName11=xilinx -LibName12=special -LibName13=microcontrollers -LibName14=dsp -LibName15=microchip -LibName16=analog_switches -LibName17=motorola -LibName18=texas -LibName19=intel -LibName20=audio -LibName21=interface -LibName22=digital-audio -LibName23=philips -LibName24=display -LibName25=cypress -LibName26=siliconi -LibName27=opto -LibName28=atmel -LibName29=contrib -LibName30=valves -[general] -version=1 -[pcbnew] -version=1 -LastNetListRead=LEDs.net -UseCmpFile=1 -PadDrill=0.6 -PadSizeH=1 -PadSizeV=1 -PcbTextSizeV=1 -PcbTextSizeH=1 -PcbTextThickness=0.3 -ModuleTextSizeV=1 -ModuleTextSizeH=1 -ModuleTextSizeThickness=0.15 -SolderMaskClearance=0 -SolderMaskMinWidth=0 -DrawSegmentWidth=0.2 -BoardOutlineThickness=0.15 -ModuleOutlineThickness=0.15 -[pcbnew/libraries] -LibDir= -LibName1=sockets -LibName2=connect -LibName3=discret -LibName4=pin_array -LibName5=divers -LibName6=libcms -LibName7=display -LibName8=led -LibName9=dip_sockets -LibName10=pga_sockets -LibName11=valves -LibName12=my_modules diff --git a/Timelapse_keyboard/kicad/my_modules.mod b/Timelapse_keyboard/kicad/my_modules.mod deleted file mode 100644 index 3d41143..0000000 --- a/Timelapse_keyboard/kicad/my_modules.mod +++ /dev/null @@ -1,1851 +0,0 @@ -PCBNEW-LibModule-V1 Пн 01 дек 2014 09:34:38 -# encoding utf-8 -Units mm -$INDEX -AC_220 -DB9-F -DB9-M -HXQFN16 -IRM-10 -MICRO-B-USB -MINI-B-USB -SIL-2-power -SIL-4-power -SIL-7 -SIP-4 -SIP-4-RO -SM-2010 -SOT-223 -SOT323 -SPST -TO220-3-vert -TO220-5 -TO220-7-12 -VASCH10x2 -gprm1-61 -hole_3mm -$EndINDEX -$MODULE AC_220 -Po 0 0 0 15 5461D5A9 00000000 ~~ -Li AC_220 -Sc 0 -AR /546621E5 -Op 0 0 0 -T0 0 -4.6 1.5 1.5 0 0.3 N V 21 N "P1" -T1 0 5.6 1.5 1.5 0 0.3 N V 21 N "AC_220" -DS -8 3.25 -8 -2.75 0.3 21 -DS -8 -2.75 7.5 -2.75 0.3 21 -DS 7.5 -2.75 7.5 3.25 0.3 21 -DS 7.5 3.25 -8 3.25 0.3 21 -$PAD -Sh "2" C 3 3 0 0 900 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 2 "N-0000031" -Po 5 0 -$EndPAD -$PAD -Sh "1" C 3 3 0 0 900 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 1 "N-0000030" -Po -5 0 -$EndPAD -$EndMODULE AC_220 -$MODULE DB9-F -Po 0 0 0 15 546362FD 00000000 ~~ -Li DB9-F -Cd Connecteur DB9 femelle couche -Kw CONN DB9 -Sc 0 -AR /53973803/53974779/53AB4443 -Op 0 0 0 -T0 -6.3 -5.3 1.524 1.524 0 0.3048 N V 21 N "XP**" -T1 7.7 -5.1 1.524 1.524 0 0.3048 N V 21 N "DB9F" -DS -16.129 2.286 16.383 2.286 0.3048 21 -DS 16.383 2.286 16.383 -9.494 0.3048 21 -DS 16.383 -9.494 -16.129 -9.494 0.3048 21 -DS -16.129 -9.494 -16.129 2.286 0.3048 21 -DS -9.017 -7.874 9.271 -7.874 0.3048 21 -$PAD -Sh "" C 3.81 3.81 0 0 0 -Dr 3.048 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 12.827 -1.27 -$EndPAD -$PAD -Sh "" C 3.81 3.81 0 0 0 -Dr 3.048 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -12.573 -1.27 -$EndPAD -$PAD -Sh "1" R 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -5.461 1.27 -$EndPAD -$PAD -Sh "2" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 2 "N-00000158" -Po -2.667 1.27 -$EndPAD -$PAD -Sh "3" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 3 "N-00000170" -Po 0 1.27 -$EndPAD -$PAD -Sh "4" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 2.794 1.27 -$EndPAD -$PAD -Sh "5" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 1 "GND" -Po 5.588 1.27 -$EndPAD -$PAD -Sh "6" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -4.064 -1.27 -$EndPAD -$PAD -Sh "7" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.27 -1.27 -$EndPAD -$PAD -Sh "8" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.397 -1.27 -$EndPAD -$PAD -Sh "9" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 4.191 -1.27 -$EndPAD -$SHAPE3D -Na "conn_DBxx/db9_female_pin90deg.wrl" -Sc 1 1 1 -Of 0 0 0 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE DB9-F -$MODULE DB9-M -Po 0 0 0 15 546363D8 00000000 ~~ -Li DB9-M -Cd Connecteur DB9 male couche -Kw CONN DB9 -Sc 0 -AR -Op 0 0 0 -T0 5.8 -5.2 1.524 1.524 0 0.3048 N V 21 N "DB9-M" -T1 -7 -4.8 1.524 1.524 0 0.3048 N V 21 N "XS**" -DS -16.129 2.286 16.383 2.286 0.3048 21 -DS 16.383 2.286 16.383 -9.494 0.3048 21 -DS 16.383 -9.494 -16.129 -9.494 0.3048 21 -DS -16.129 -9.494 -16.129 2.286 0.3048 21 -DS -9.017 -7.874 9.271 -7.874 0.3048 21 -$PAD -Sh "" C 3.81 3.81 0 0 0 -Dr 3.048 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 12.827 -1.27 -$EndPAD -$PAD -Sh "" C 3.81 3.81 0 0 0 -Dr 3.048 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -12.573 -1.27 -$EndPAD -$PAD -Sh "1" R 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 5.588 1.27 -$EndPAD -$PAD -Sh "2" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 2.794 1.27 -$EndPAD -$PAD -Sh "3" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 0 1.27 -$EndPAD -$PAD -Sh "4" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -2.667 1.27 -$EndPAD -$PAD -Sh "5" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -5.461 1.27 -$EndPAD -$PAD -Sh "9" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -4.064 -1.27 -$EndPAD -$PAD -Sh "8" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.27 -1.27 -$EndPAD -$PAD -Sh "7" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.397 -1.27 -$EndPAD -$PAD -Sh "6" C 1.524 1.524 0 0 0 -Dr 1.016 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 4.191 -1.27 -$EndPAD -$SHAPE3D -Na "conn_DBxx/db9_male_pin90deg.wrl" -Sc 1 1 1 -Of 0 0 0 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE DB9-M -$MODULE HXQFN16 -Po 0 0 0 15 547C0BEB 00000000 ~~ -Li HXQFN16 -Sc 0 -AR -Op 0 0 0 -T0 0 -2.3 0.14986 0.14986 0 0.0381 N V 21 N "Test" -T1 0 2.3 0.14986 0.14986 0 0.0381 N V 21 N "VAL**" -DS -1 1.6 -1.5 1 0.15 21 -DS -1.5 1 -1.8 1 0.15 21 -DS -1.8 1 -1 2 0.15 21 -DS -1 2 -1 1.6 0.15 21 -DS 1.5 1.1 1.5 1.2 0.15 21 -DS 1.5 1.2 1.5 1.5 0.15 21 -DS 1.5 1.5 1.1 1.5 0.15 21 -DS -1.5 -1.1 -1.5 -1.5 0.15 21 -DS -1.5 -1.5 -1.1 -1.5 0.15 21 -DS 1.5 -1.5 1.5 -1.1 0.15 21 -DS 1.1 -1.5 1.5 -1.5 0.15 21 -$PAD -Sh "1" R 0.3 0.6 0 0 1800 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -0.75 1.5 -$EndPAD -$PAD -Sh "2" R 0.3 0.6 0 0 1800 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -0.25 1.5 -$EndPAD -$PAD -Sh "3" R 0.3 0.6 0 0 1800 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0.25 1.5 -$EndPAD -$PAD -Sh "4" R 0.3 0.6 0 0 1800 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0.75 1.5 -$EndPAD -$PAD -Sh "5" R 0.3 0.6 0 0 2700 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.5 0.75 -$EndPAD -$PAD -Sh "6" R 0.3 0.6 0 0 2700 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.5 0.25 -$EndPAD -$PAD -Sh "7" R 0.3 0.6 0 0 2700 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.5 -0.25 -$EndPAD -$PAD -Sh "8" R 0.3 0.6 0 0 2700 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.5 -0.75 -$EndPAD -$PAD -Sh "9" R 0.3 0.6 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0.75 -1.5 -$EndPAD -$PAD -Sh "10" R 0.3 0.6 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0.25 -1.5 -$EndPAD -$PAD -Sh "11" R 0.3 0.6 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -0.25 -1.5 -$EndPAD -$PAD -Sh "12" R 0.3 0.6 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -0.75 -1.5 -$EndPAD -$PAD -Sh "13" R 0.3 0.6 0 0 900 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.5 -0.75 -$EndPAD -$PAD -Sh "14" R 0.3 0.6 0 0 900 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.5 -0.25 -$EndPAD -$PAD -Sh "15" R 0.3 0.6 0 0 900 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.5 0.25 -$EndPAD -$PAD -Sh "16" R 0.3 0.6 0 0 900 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.5 0.75 -$EndPAD -$PAD -Sh "nc" R 1.85 1.85 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0 0 -$EndPAD -$EndMODULE HXQFN16 -$MODULE IRM-10 -Po 0 0 0 15 5461D14B 00000000 ~~ -Li IRM-10 -Sc 0 -AR -Op 0 0 0 -T0 0 0 1.5 1.5 0 0.3 N V 21 N "IRM-10" -T1 0 -8.5 1.5 1.5 0 0.3 N V 21 N "VAL**" -T2 19.5 6 1.5 1.5 0 0.3 N V 21 N "GND" -T2 18.5 -2 1.5 1.5 0 0.3 N V 21 N "+5V" -T2 -17 4 1.5 1.5 0 0.3 N V 21 N "AC 220V" -DS 22.85 -12.7 22.85 12.7 0.3 21 -DS -22.85 12.7 22.85 12.7 0.3 21 -DS -22.85 -12.7 -22.85 12.7 0.3 21 -DS -22.85 -12.7 22.85 -12.7 0.3 21 -$PAD -Sh "3" C 3 3 0 0 0 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 19.25 9.25 -$EndPAD -$PAD -Sh "4" C 3 3 0 0 0 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 19.25 1.25 -$EndPAD -$PAD -Sh "2" C 3 3 0 0 0 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -19.25 9.25 -$EndPAD -$PAD -Sh "1" C 3 3 0 0 0 -Dr 1.5 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -19.25 -1.5 -$EndPAD -$EndMODULE IRM-10 -$MODULE MICRO-B-USB -Po 0 0 0 15 53BBEC87 00000000 ~~ -Li MICRO-B-USB -Sc 0 -AR -Op 0 0 0 -T0 0 -5.842 0.762 0.762 0 0.127 N V 21 N "MICRO-B-USB" -T1 -0.05 2.09 0.762 0.762 0 0.127 N V 21 N "VAL**" -DS -4.0005 1.00076 -4.0005 1.19888 0.09906 21 -DS 4.0005 1.00076 4.0005 1.19888 0.09906 21 -DS -4.0005 -4.39928 4.0005 -4.39928 0.09906 21 -DS 4.0005 -4.39928 4.0005 1.00076 0.09906 21 -DS 4.0005 1.19888 -4.0005 1.19888 0.09906 21 -DS -4.0005 1.00076 -4.0005 -4.39928 0.09906 21 -$PAD -Sh "7" R 1.89738 1.89738 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.19888 -1.4478 -$EndPAD -$PAD -Sh "8" R 1.89992 1.89738 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.19888 -1.4478 -$EndPAD -$PAD -Sh "9" R 1.79578 1.89738 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 3.79984 -1.4478 -$EndPAD -$PAD -Sh "" R 2.0955 1.59766 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -3.0988 -3.99796 -$EndPAD -$PAD -Sh "1" R 0.39878 1.3462 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -1.29794 -4.12496 -.LocalClearance 0.2032 -$EndPAD -$PAD -Sh "2" R 0.39878 1.3462 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -0.6477 -4.12496 -.LocalClearance 0.2032 -$EndPAD -$PAD -Sh "3" R 0.39878 1.3462 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0 -4.12496 -.LocalClearance 0.2032 -$EndPAD -$PAD -Sh "4" R 0.39878 1.3462 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0.6477 -4.12496 -.LocalClearance 0.2032 -$EndPAD -$PAD -Sh "5" R 0.39878 1.3462 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 1.29794 -4.12496 -.LocalClearance 0.2032 -$EndPAD -$PAD -Sh "" R 2.0955 1.59766 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 3.0988 -3.99796 -$EndPAD -$PAD -Sh "6" R 1.79578 1.89738 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -3.79984 -1.4478 -$EndPAD -$EndMODULE MICRO-B-USB -$MODULE MINI-B-USB -Po 0 0 0 15 54749293 00000000 ~~ -Li MINI-B-USB -Sc 0 -AR /53973803/53976CAB/53BE6988 -Op 0 0 0 -T0 -4.1275 -5.4045 0.762 0.762 0 0.127 N V 21 N "CON1" -T1 4.8895 -5.4045 0.762 0.762 0 0.127 N V 21 N "USB-MICRO-B" -DS -6 5 -6 -4.5 0.3 21 -DS 6 -4.5 6 5 0.3 21 -DS 6 5 -6 5 0.3 21 -DS 6 -4.5 -6 -4.5 0.3 21 -DS -8 5.85 8 5.85 0.3 21 -$PAD -Sh "" C 0.9 0.9 0 0 0 -Dr 0.9 0 0 -At STD N 0020FFFF -Ne 0 "" -Po 2.2 0 -$EndPAD -$PAD -Sh "7" R 2 2.5 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po -4.45 2.87 -$EndPAD -$PAD -Sh "8" R 2 2.5 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po 4.45 -2.58 -$EndPAD -$PAD -Sh "9" R 2 2.5 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po 4.45 2.87 -$EndPAD -$PAD -Sh "1" R 0.5 2.25 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 4 "N-00000175" -Po -1.6 -2.58 -.LocalClearance 0.1 -$EndPAD -$PAD -Sh "2" R 0.5 2.25 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 3 "N-00000171" -Po -0.8 -2.58 -.LocalClearance 0.1 -$EndPAD -$PAD -Sh "3" R 0.5 2.25 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 2 "N-00000170" -Po 0 -2.58 -.LocalClearance 0.1 -$EndPAD -$PAD -Sh "4" R 0.5 2.25 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po 0.8 -2.58 -.LocalClearance 0.1 -$EndPAD -$PAD -Sh "5" R 0.5 2.25 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po 1.6 -2.58 -.LocalClearance 0.1 -$EndPAD -$PAD -Sh "6" R 2 2.5 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "GND" -Po -4.45 -2.58 -$EndPAD -$PAD -Sh "" C 0.9 0.9 0 0 0 -Dr 0.9 0 0 -At STD N 0020FFFF -Ne 0 "" -Po -2.2 0 -$EndPAD -$EndMODULE MINI-B-USB -$MODULE SIL-2-power -Po 0 0 0 15 53BBF457 00000000 ~~ -Li SIL-2-power -Cd Connecteurs 2 pins -Kw CONN DEV -Sc 0 -AR /53931287 -Op 0 0 0 -T0 0 -4.064 1.72974 1.08712 0 0.3048 N V 21 N "P1" -T1 0 3.81 1.524 1.016 0 0.3048 N I 21 N "CONN_2" -DS -5.08 -2.54 5.08 -2.54 0.3 21 -DS 5.08 -2.54 5.08 2.54 0.3 21 -DS 5.08 2.54 -5.08 2.54 0.3 21 -DS -5.08 2.54 -5.08 -2.54 0.3 21 -$PAD -Sh "1" R 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 2 "GND" -Po -2.54 0 -$EndPAD -$PAD -Sh "2" C 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 1 "/Filters slit #1/+10V" -Po 2.54 0 -$EndPAD -$EndMODULE SIL-2-power -$MODULE SIL-4-power -Po 0 0 0 15 53BD461C 00000000 ~~ -Li SIL-4-power -Cd Connecteur 4 pibs -Kw CONN DEV -Sc 0 -AR /5392E6AB -Op 0 0 0 -T0 0 -3.81 1.73482 1.08712 0 0.3048 N V 21 N "P2" -T1 0 3.81 1.524 1.016 0 0.3048 N I 21 N "CONN_4" -DS -5.08 -2.54 -5.08 2.54 0.3 21 -DS -10.16 2.54 10.16 2.54 0.3 21 -DS 10.16 2.54 10.16 -2.54 0.3 21 -DS 10.16 -2.54 -10.16 -2.54 0.3 21 -DS -10.16 -2.54 -10.16 2.54 0.3 21 -DS -5.08 -1.27 -5.08 -1.27 0.3048 21 -DS -5.08 -1.27 -5.08 -1.27 0.3048 21 -$PAD -Sh "1" R 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 1 "/Turret slits/A" -Po -7.62 0 -$EndPAD -$PAD -Sh "2" C 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 2 "/Turret slits/A*" -Po -2.54 0 -$EndPAD -$PAD -Sh "3" C 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 3 "/Turret slits/B" -Po 2.54 0 -$EndPAD -$PAD -Sh "4" C 3.5 3.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 4 "/Turret slits/B*" -Po 7.62 0 -$EndPAD -$EndMODULE SIL-4-power -$MODULE SIL-7 -Po 0 0 0 15 5461EE54 00000000 ~~ -Li SIL-7 -Cd Connecteur 7 pins -Kw CONN DEV -Sc 0 -AR /53973803/53A363AA -Op 0 0 0 -T0 -2.1209 2.8194 1.72974 1.08712 0 0.27178 N V 21 N "XP5" -T1 0 -2.54 1.524 1.016 0 0.3048 N I 21 N "CONN_7" -DS -8.89 -1.27 -8.89 -1.27 0.3048 21 -DS -8.89 -1.27 8.89 -1.27 0.3048 21 -DS 8.89 -1.27 8.89 1.27 0.3048 21 -DS 8.89 1.27 -8.89 1.27 0.3048 21 -DS -8.89 1.27 -8.89 -1.27 0.3048 21 -DS -6.35 1.27 -6.35 1.27 0.3048 21 -DS -6.35 1.27 -6.35 -1.27 0.3048 21 -$PAD -Sh "1" R 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 7 "GND" -Po -7.62 0 -$EndPAD -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 1 "/STM32F103 module/EXT0" -Po -5.08 0 -$EndPAD -$PAD -Sh "3" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 2 "/STM32F103 module/EXT1" -Po -2.54 0 -$EndPAD -$PAD -Sh "4" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 3 "/STM32F103 module/EXT2" -Po 0 0 -$EndPAD -$PAD -Sh "5" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 4 "/STM32F103 module/EXT3" -Po 2.54 0 -$EndPAD -$PAD -Sh "6" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 5 "/STM32F103 module/RS-232 level converter/UART_RX1" -Po 5.08 0 -$EndPAD -$PAD -Sh "7" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00F0FFFF -Ne 6 "/STM32F103 module/RS-232 level converter/UART_TX1" -Po 7.62 0 -$EndPAD -$EndMODULE SIL-7 -$MODULE SIP-4 -Po 0 0 0 15 53BBF76F 00000000 ~~ -Li SIP-4 -Sc 0 -AR /53AC9E48 -Op 0 0 0 -T0 0 2.54 1 1 0 0.15 N V 21 N "Q3" -T1 0 -3.175 1 1 0 0.15 N V 21 N "RO-1224" -DS 5.715 1.27 -5.715 1.27 0.15 21 -DS -5.715 1.27 -5.715 -4.445 0.15 21 -DS -5.715 -4.445 5.715 -4.445 0.15 21 -DS 5.715 -4.445 5.715 1.27 0.15 21 -$PAD -Sh "3" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 2 "/Filters slit #1/+24V" -Po 1.27 0 -$EndPAD -$PAD -Sh "4" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 3 "GND" -Po 3.81 0 -$EndPAD -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 3 "GND" -Po -1.27 0 -$EndPAD -$PAD -Sh "1" R 1.5 2 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 1 "/Filters slit #1/+10V" -Po -3.81 0 -$EndPAD -$EndMODULE SIP-4 -$MODULE SIP-4-RO -Po 0 0 0 15 53BBF819 00000000 ~~ -Li SIP-4-RO -Sc 0 -AR /53AC9E48 -Op 0 0 0 -T0 0 2.54 1 1 0 0.15 N V 21 N "Q3" -T1 0 -3.175 1 1 0 0.15 N V 21 N "RO-1224" -DS 5.715 1.27 -5.715 1.27 0.15 21 -DS -5.715 1.27 -5.715 -4.445 0.15 21 -DS -5.715 -4.445 5.715 -4.445 0.15 21 -DS 5.715 -4.445 5.715 1.27 0.15 21 -$PAD -Sh "3" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 2 "/Filters slit #1/+24V" -Po 1.27 0 -$EndPAD -$PAD -Sh "4" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 3 "GND" -Po 3.81 0 -$EndPAD -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 3 "GND" -Po -1.27 0 -$EndPAD -$PAD -Sh "1" R 1.5 2 0 0 0 -Dr 0.6 0 0 -At STD N 00E0FFFF -Ne 1 "/Filters slit #1/+10V" -Po -3.81 0 -$EndPAD -$EndMODULE SIP-4-RO -$MODULE SM-2010 -Po 0 0 0 15 54620775 00000000 ~~ -Li SM-2010 -Kw CMS SM -Sc 0 -AR -Op 0 0 0 -At SMD -T0 0 -2.4 0.70104 0.70104 0 0.127 N V 21 N "SM-2010" -T1 0 2.7 0.70104 0.70104 0 0.127 N I 21 N "VAL**" -DS 3.50012 -1.6002 3.50012 1.6002 0.11938 21 -DS -3.50012 -1.6002 -3.50012 1.6002 0.11938 21 -DS 1.19634 1.60528 3.48234 1.60528 0.11938 21 -DS 3.48234 -1.60528 1.19634 -1.60528 0.11938 21 -DS -1.19888 -1.60528 -3.48488 -1.60528 0.11938 21 -DS -3.48488 1.60528 -1.19888 1.60528 0.11938 21 -$PAD -Sh "1" R 1.80086 2.70002 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -2.4003 0 -$EndPAD -$PAD -Sh "2" R 1.80086 2.70002 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 2.4003 0 -$EndPAD -$SHAPE3D -Na "smd\\chip_smd_pol_wide.wrl" -Sc 0.35 0.35 0.35 -Of 0 0 0 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE SM-2010 -$MODULE SOT-223 -Po 0 0 0 15 53BBED5D 00000000 ~~ -Li SOT-223 -Cd module CMS SOT223 4 pins -Kw CMS SOT -Sc 0 -AR -Op 0 0 0 -At SMD -T0 0 -0.762 1.016 1.016 0 0.2032 N V 21 N "SOT-223" -T1 0 0.762 1.016 1.016 0 0.2032 N V 21 N "Val**" -DS -3.556 1.524 -3.556 4.572 0.2032 21 -DS -3.556 4.572 3.556 4.572 0.2032 21 -DS 3.556 4.572 3.556 1.524 0.2032 21 -DS -3.556 -1.524 -3.556 -2.286 0.2032 21 -DS -3.556 -2.286 -2.032 -4.572 0.2032 21 -DS -2.032 -4.572 2.032 -4.572 0.2032 21 -DS 2.032 -4.572 3.556 -2.286 0.2032 21 -DS 3.556 -2.286 3.556 -1.524 0.2032 21 -$PAD -Sh "4" R 3.6576 2.032 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0 -3.302 -$EndPAD -$PAD -Sh "2" R 1.016 2.032 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 0 3.302 -$EndPAD -$PAD -Sh "3" R 1.016 2.032 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po 2.286 3.302 -$EndPAD -$PAD -Sh "1" R 1.016 2.032 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 0 "" -Po -2.286 3.302 -$EndPAD -$SHAPE3D -Na "smd/SOT223.wrl" -Sc 0.4 0.4 0.4 -Of 0 0 0 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE SOT-223 -$MODULE SOT323 -Po 0 0 0 15 450AC34A 00000000 ~~ -Li SOT323 -Kw SMD SOT -Sc 0 -AR /53973803/53976CAB/5395C059 -Op 0 0 0 -At SMD -T0 0.127 -2.032 0.762 0.762 0 0.09906 N V 21 N "Q1" -T1 0 0 0.70104 0.70104 0 0.09906 N I 21 N "DTA114Y" -DS 0.254 0.508 0.889 0.508 0.127 21 -DS 0.889 0.508 0.889 -0.508 0.127 21 -DS -0.889 -0.508 -0.889 0.508 0.127 21 -DS -0.889 0.508 -0.254 0.508 0.127 21 -DS 0.254 0.635 0.254 0.508 0.127 21 -DS -0.254 0.508 -0.254 0.635 0.127 21 -DS 0.889 -0.508 -0.889 -0.508 0.127 21 -DS -0.254 0.635 0.254 0.635 0.127 21 -$PAD -Sh "2" R 0.59944 1.00076 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 1 "+3.3V" -Po -0.65024 -0.94996 -$EndPAD -$PAD -Sh "1" R 0.59944 1.00076 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 2 "/STM32F103 module/USB input circuit/USB_DISC" -Po 0.65024 -0.94996 -$EndPAD -$PAD -Sh "3" R 0.59944 1.00076 0 0 0 -Dr 0 0 0 -At SMD N 00888000 -Ne 3 "N-00000154" -Po 0 0.94996 -$EndPAD -$SHAPE3D -Na "smd/SOT323.wrl" -Sc 0.3937 0.3937 0.3937 -Of 0 0 0.001 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE SOT323 -$MODULE SPST -Po 0 0 0 15 53CCACAB 00000000 ~~ -Li SPST -Sc 0 -AR -Op 0 0 0 -T0 0 -4.445 1.016 1.016 0 0.2032 N V 21 N "SPST" -T1 0 4.572 1.016 1.016 0 0.2032 N V 21 N "Val**" -DC 0 0 1.27 1.651 0.3 21 -DS 4.572 -3.556 4.572 3.556 0.3 21 -DS -4.572 3.556 4.572 3.556 0.3 21 -DS -4.572 -3.556 4.572 -3.556 0.3 21 -DS -4.572 -3.556 -4.572 3.556 0.3 21 -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 3.25 2.25 -$EndPAD -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -3.25 2.25 -$EndPAD -$PAD -Sh "1" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -3.25 -2.25 -$EndPAD -$PAD -Sh "1" C 1.5 1.5 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 3.25 -2.25 -$EndPAD -$EndMODULE SPST -$MODULE TO220-3-vert -Po 0 0 0 15 546217E8 00000000 ~~ -Li TO220-3-vert -Cd Transistor TO 220 -Kw TR TO220 DEV -Sc 0 -AR /53AA0E2D/53AF4F62 -Op 0 0 0 -T0 0 -5.715 1.016 1.016 0 0.2032 N V 21 N "VT2.1" -T1 6.751 0.174 1.016 1.016 900 0.2032 N V 21 N "FQP30N06" -DS 4.445 -4.445 -4.445 -4.445 0.3 21 -DS -4.445 -4.445 -4.445 4.445 0.3 21 -DS -4.445 4.445 4.445 4.445 0.3 21 -DS 4.445 4.445 4.445 -4.445 0.3 21 -DS 4.445 -4.445 5.715 -4.445 0.3 21 -DS 5.715 -4.445 5.715 4.445 0.3 21 -DS 5.715 4.445 4.445 4.445 0.3 21 -$PAD -Sh "1" R 3 3 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 3 "N-00000150" -Po 2.54 -2.54 -$EndPAD -$PAD -Sh "2" C 3 3 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 1 "/Power MOSFET module 2/GND_OUT" -Po -2.54 0 -$EndPAD -$PAD -Sh "3" C 3 3 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 2 "GND" -Po 2.54 2.54 -$EndPAD -$SHAPE3D -Na "discret/to220_horiz.wrl" -Sc 1 1 1 -Of 0 0 0 -Ro 0 0 0 -$EndSHAPE3D -$EndMODULE TO220-3-vert -$MODULE TO220-5 -Po 0 0 0 15 5461EDB0 00000000 ~~ -Li TO220-5 -Cd Regulateur TO220 serie LM78xx -Kw TR TO220 -Sc 0 -AR -Op 0 0 0 -T0 -4.445 0 1.524 1.016 900 0.2032 N V 21 N "TO220-5" -T1 0 -6.35 1.524 1.016 0 0.2032 N V 21 N "VAL**" -DS 3.175 5.08 -3.175 5.08 0.381 21 -DS -3.175 -5.08 3.175 -5.08 0.381 21 -DS 3.175 -5.08 3.81 -5.08 0.381 21 -DS 3.81 -5.08 3.81 5.08 0.381 21 -DS 3.81 5.08 3.175 5.08 0.381 21 -DS 3.175 -5.08 3.175 5.08 0.381 21 -DS -3.175 5.08 -3.175 -5.08 0.381 21 -$PAD -Sh "1" R 2 2 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.7 -3.4 -$EndPAD -$PAD -Sh "5" C 2 2 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.7 3.4 -$EndPAD -$PAD -Sh "2" C 2 2 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.7 -1.7 -$EndPAD -$PAD -Sh "3" C 2 2 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.7 0 -$EndPAD -$PAD -Sh "4" C 2 2 0 0 0 -Dr 1 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.7 1.7 -$EndPAD -$EndMODULE TO220-5 -$MODULE TO220-7-12 -Po 0 0 0 15 5461EDEF 00000000 ~~ -Li TO220-7-12 -Cd Regulateur TO220 serie LM78xx -Kw TR TO220 -Sc 0 -AR -Op 0 0 0 -T0 -4.445 0 1.524 1.016 900 0.2032 N V 21 N "TO220-7-12" -T1 0 -6.35 1.524 1.016 0 0.2032 N V 21 N "VAL**" -DS 3.175 5.08 -3.175 5.08 0.381 21 -DS -3.175 -5.08 3.175 -5.08 0.381 21 -DS 3.175 -5.08 3.81 -5.08 0.381 21 -DS 3.81 -5.08 3.81 5.08 0.381 21 -DS 3.81 5.08 3.175 5.08 0.381 21 -DS 3.175 -5.08 3.175 5.08 0.381 21 -DS -3.175 5.08 -3.175 -5.08 0.381 21 -$PAD -Sh "7" C 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.27 3.81 -$EndPAD -$PAD -Sh "1" R 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.27 -3.81 -$EndPAD -$PAD -Sh "5" C 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.27 1.27 -$EndPAD -$PAD -Sh "6" C 1.5 1.5 0 0 0 -Dr 0.9 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.27 2.54 -$EndPAD -$PAD -Sh "2" C 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.27 -2.54 -$EndPAD -$PAD -Sh "3" C 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 1.27 -1.27 -$EndPAD -$PAD -Sh "4" C 1.5 1.5 0 0 0 -Dr 0.8 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -1.27 0 -$EndPAD -$EndMODULE TO220-7-12 -$MODULE VASCH10x2 -Po 0 0 0 15 543F7EC1 00000000 ~~ -Li VASCH10x2 -Cd CONNECTOR -Kw CONNECTOR -Sc 0 -AR /53CA50BA -Op 0 0 0 -At VIRTUAL -T0 -15.875 -5.715 1.778 1.778 0 0.0889 N V 21 N "XP7" -T1 0 6.35 1.778 1.778 0 0.0889 N V 21 N "Power" -DS 15.875 3.81 16.51 4.445 0.254 21 -DS 15.875 -3.81 16.51 -4.445 0.254 21 -DS -15.875 3.81 -16.51 4.445 0.254 21 -DS -16.51 -4.445 -15.875 -3.81 0.254 21 -DS -15.875 -3.81 -15.875 3.81 0.254 21 -DS -15.875 3.81 -1.905 3.81 0.254 21 -DS -1.905 3.81 -1.905 4.445 0.254 21 -DS -15.875 -3.81 15.875 -3.81 0.254 21 -DS 15.875 -3.81 15.875 3.81 0.254 21 -DS 15.875 3.81 1.905 3.81 0.254 21 -DS 1.905 3.81 1.905 4.445 0.254 21 -DS 16.51 -4.445 -16.51 -4.445 0.254 21 -DS -16.51 4.445 16.51 4.445 0.254 21 -DS -16.51 -4.445 -16.51 4.445 0.254 21 -DS 16.51 -4.445 16.51 4.445 0.254 21 -DS -13.84808 1.9685 -13.14958 3.03784 0.254 21 -DS -13.14958 3.03784 -12.44854 1.9685 0.254 21 -DS -12.44854 1.9685 -13.84808 1.9685 0.254 21 -$PAD -Sh "1" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 4 "/Shutter MOSFET/OUT1" -Po -11.43 1.27 -$EndPAD -$PAD -Sh "2" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 4 "/Shutter MOSFET/OUT1" -Po -11.43 -1.27 -$EndPAD -$PAD -Sh "3" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 4 "/Shutter MOSFET/OUT1" -Po -8.89 1.27 -$EndPAD -$PAD -Sh "4" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 4 "/Shutter MOSFET/OUT1" -Po -8.89 -1.27 -$EndPAD -$PAD -Sh "5" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 5 "/Shutter MOSFET/OUT2" -Po -6.35 1.27 -$EndPAD -$PAD -Sh "6" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 5 "/Shutter MOSFET/OUT2" -Po -6.35 -1.27 -$EndPAD -$PAD -Sh "7" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 5 "/Shutter MOSFET/OUT2" -Po -3.81 1.27 -$EndPAD -$PAD -Sh "8" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 5 "/Shutter MOSFET/OUT2" -Po -3.81 -1.27 -$EndPAD -$PAD -Sh "9" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 0 "" -Po -1.27 1.27 -$EndPAD -$PAD -Sh "10" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 0 "" -Po -1.27 -1.27 -$EndPAD -$PAD -Sh "11" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 2 "/Power MOSFET module 1/GND_OUT" -Po 1.27 1.27 -$EndPAD -$PAD -Sh "12" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 2 "/Power MOSFET module 1/GND_OUT" -Po 1.27 -1.27 -$EndPAD -$PAD -Sh "13" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 1 "/Filters slit #1/+10V" -Po 3.81 1.27 -$EndPAD -$PAD -Sh "14" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 1 "/Filters slit #1/+10V" -Po 3.81 -1.27 -$EndPAD -$PAD -Sh "15" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 0 "" -Po 6.35 1.27 -$EndPAD -$PAD -Sh "16" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 0 "" -Po 6.35 -1.27 -$EndPAD -$PAD -Sh "17" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 1 "/Filters slit #1/+10V" -Po 8.89 1.27 -$EndPAD -$PAD -Sh "18" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 1 "/Filters slit #1/+10V" -Po 8.89 -1.27 -$EndPAD -$PAD -Sh "19" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 3 "/Power MOSFET module 2/GND_OUT" -Po 11.43 1.27 -$EndPAD -$PAD -Sh "20" C 1.50622 1.50622 0 0 0 -Dr 0.99822 0 0 -At STD N 00E8FFFF -Ne 3 "/Power MOSFET module 2/GND_OUT" -Po 11.43 -1.27 -$EndPAD -$EndMODULE VASCH10x2 -$MODULE gprm1-61 -Po 0 0 0 15 54620BAD 00000000 ~~ -Li gprm1-61 -Sc 0 -AR /53DA1715 -Op 0 0 0 -At SMD -T0 0 -0.381 0.508 0.508 0 0.1016 N V 21 N "XP1" -T1 0 0.381 0.508 0.508 0 0.1016 N I 21 N "GPRM1-61" -DS -64.9986 -9.99998 64.9986 -9.99998 0.19812 21 -DS 64.9986 4.99872 -64.9986 4.99872 0.19812 21 -DS -64.9986 -5.4991 -64.9986 4.99872 0.19812 21 -DS -64.9986 -9.99998 64.9986 -9.99998 0.19812 21 -DS 64.9986 -5.4991 -64.9986 -5.4991 0.19812 21 -DS 64.9986 -5.4991 64.9986 4.99872 0.19812 21 -DS -64.9986 -9.99998 64.9986 -9.99998 0.19812 21 -DS 64.9986 4.99872 -64.9986 4.99872 0.19812 21 -DS -64.9986 -5.4991 -64.9986 4.99872 0.19812 21 -DS -64.9986 -9.99998 64.9986 -9.99998 0.19812 21 -DS 64.9986 -5.4991 -64.9986 -5.4991 0.19812 21 -DS 64.9986 -5.4991 64.9986 4.99872 0.19812 21 -$PAD -Sh "1-1" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 31 "/STM32F103 module/1-WIRE" -Po -50.74666 3.49758 -$EndPAD -$PAD -Sh "1-2" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 1 "+5V" -Po -47.24654 3.49758 -$EndPAD -$PAD -Sh "1-3" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -43.74642 3.49758 -$EndPAD -$PAD -Sh "1-4" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -40.2463 3.49758 -$EndPAD -$PAD -Sh "1-5" O 1.79832 1.80086 0 0 0 -Dr 0.79756 0 0 -At STD N 00CCFFFF -Ne 30 "/POW_LOAD" -Po -36.74872 3.49758 -$EndPAD -$PAD -Sh "1-6" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 30 "/POW_LOAD" -Po -33.2486 3.49758 -$EndPAD -$PAD -Sh "1-7" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -29.74848 3.49758 -$EndPAD -$PAD -Sh "1-8" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -26.24836 3.49758 -$EndPAD -$PAD -Sh "1-9" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -22.74824 3.49758 -$EndPAD -$PAD -Sh "1-10" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po -19.24812 3.49758 -$EndPAD -$PAD -Sh "1-11" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 37 "/Turret slits/A" -Po -15.748 3.49758 -$EndPAD -$PAD -Sh "1-12" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 38 "/Turret slits/A*" -Po -12.24788 3.49758 -$EndPAD -$PAD -Sh "1-13" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 39 "/Turret slits/B" -Po -8.74776 3.49758 -$EndPAD -$PAD -Sh "1-14" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 40 "/Turret slits/B*" -Po -5.24764 3.49758 -$EndPAD -$PAD -Sh "1-15" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 8 "/Filters slit #1/A" -Po -1.74752 3.49758 -$EndPAD -$PAD -Sh "1-16" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 9 "/Filters slit #1/A*" -Po 1.74752 3.49758 -$EndPAD -$PAD -Sh "1-17" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 10 "/Filters slit #1/B" -Po 5.24764 3.49758 -$EndPAD -$PAD -Sh "1-18" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 11 "/Filters slit #1/B*" -Po 8.74776 3.49758 -$EndPAD -$PAD -Sh "1-19" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 12 "/Filters slit #2/A" -Po 12.24788 3.49758 -$EndPAD -$PAD -Sh "1-20" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 13 "/Filters slit #2/A*" -Po 15.748 3.49758 -$EndPAD -$PAD -Sh "1-21" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 14 "/Filters slit #2/B" -Po 19.24812 3.49758 -$EndPAD -$PAD -Sh "1-22" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 15 "/Filters slit #2/B*" -Po 22.74824 3.49758 -$EndPAD -$PAD -Sh "1-23" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 26 "/Long stage/A" -Po 26.24836 3.49758 -$EndPAD -$PAD -Sh "1-24" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 27 "/Long stage/A*" -Po 29.74848 3.49758 -$EndPAD -$PAD -Sh "1-25" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 28 "/Long stage/B" -Po 33.2486 3.49758 -$EndPAD -$PAD -Sh "1-26" O 1.79832 1.80086 0 0 0 -Dr 0.79756 0 0 -At STD N 00CCFFFF -Ne 29 "/Long stage/B*" -Po 36.74872 3.49758 -$EndPAD -$PAD -Sh "1-27" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 32 "/Short stage/A" -Po 40.2463 3.49758 -$EndPAD -$PAD -Sh "1-28" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 33 "/Short stage/A*" -Po 43.74642 3.49758 -$EndPAD -$PAD -Sh "1-29" O 1.79832 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 34 "/Short stage/B" -Po 47.24654 3.49758 -$EndPAD -$PAD -Sh "1-30" O 1.80086 1.80086 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 35 "/Short stage/B*" -Po 50.74666 3.49758 -$EndPAD -$PAD -Sh "2-1" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 2 "/5Vext" -Po -52.49672 0 -$EndPAD -$PAD -Sh "2-2" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 25 "/Hall9" -Po -48.9966 0 -$EndPAD -$PAD -Sh "2-3" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 24 "/Hall8" -Po -45.49648 0 -$EndPAD -$PAD -Sh "2-4" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 23 "/Hall7" -Po -41.99636 0 -$EndPAD -$PAD -Sh "2-5" O 1.79832 1.79832 0 0 0 -Dr 0.79756 0 0 -At STD N 00CCFFFF -Ne 22 "/Hall6" -Po -38.49878 0 -$EndPAD -$PAD -Sh "2-6" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 21 "/Hall5" -Po -34.99866 0 -$EndPAD -$PAD -Sh "2-7" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 20 "/Hall4" -Po -31.49854 0 -$EndPAD -$PAD -Sh "2-8" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 19 "/Hall3" -Po -27.99842 0 -$EndPAD -$PAD -Sh "2-9" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 18 "/Hall2" -Po -24.4983 0 -$EndPAD -$PAD -Sh "2-10" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 17 "/Hall1" -Po -20.99818 0 -$EndPAD -$PAD -Sh "2-11" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 16 "/Hall0" -Po -17.49806 0 -$EndPAD -$PAD -Sh "2-12" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 6 "/EP3" -Po -13.99794 0 -$EndPAD -$PAD -Sh "2-13" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 5 "/EP2" -Po -10.49782 0 -$EndPAD -$PAD -Sh "2-14" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 4 "/EP1" -Po -6.9977 0 -$EndPAD -$PAD -Sh "2-15" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 3 "/EP0" -Po -3.49758 0 -$EndPAD -$PAD -Sh "2-16" O 1.79832 1.79832 0 0 0 -Dr 0.79756 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 0 0 -$EndPAD -$PAD -Sh "2-17" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 1 "+5V" -Po 3.49758 0 -$EndPAD -$PAD -Sh "2-18" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 0 "" -Po 6.9977 0 -$EndPAD -$PAD -Sh "2-19" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 10.49782 0 -$EndPAD -$PAD -Sh "2-20" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 13.99794 0 -$EndPAD -$PAD -Sh "2-21" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 17.49806 0 -$EndPAD -$PAD -Sh "2-22" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 20.99818 0 -$EndPAD -$PAD -Sh "2-23" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 41 "GND" -Po 24.4983 0 -$EndPAD -$PAD -Sh "2-24" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 0 "" -Po 27.99842 0 -$EndPAD -$PAD -Sh "2-25" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 7 "/Filters slit #1/+10V" -Po 31.49854 0 -$EndPAD -$PAD -Sh "2-26" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 7 "/Filters slit #1/+10V" -Po 34.99866 0 -$EndPAD -$PAD -Sh "2-27" O 1.79832 1.79832 0 0 0 -Dr 0.79756 0 0 -At STD N 00CCFFFF -Ne 7 "/Filters slit #1/+10V" -Po 38.49878 0 -$EndPAD -$PAD -Sh "2-28" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 7 "/Filters slit #1/+10V" -Po 41.99636 0 -$EndPAD -$PAD -Sh "2-29" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 0 "" -Po 45.49648 0 -$EndPAD -$PAD -Sh "2-30" O 1.79832 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 36 "/Shutter MOSFET/+36V" -Po 48.9966 0 -$EndPAD -$PAD -Sh "2-31" O 1.80086 1.79832 0 0 0 -Dr 0.8001 0 0 -At STD N 00CCFFFF -Ne 36 "/Shutter MOSFET/+36V" -Po 52.49672 0 -$EndPAD -$PAD -Sh "HOLE" C 2.99974 2.99974 0 0 0 -Dr 2.99974 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po -59.99734 -2.9972 -$EndPAD -$PAD -Sh "HOLE" C 2.99974 2.99974 0 0 0 -Dr 2.99974 0 0 -At STD N 00E0FFFF -Ne 0 "" -Po 59.99734 -2.9972 -$EndPAD -$EndMODULE gprm1-61 -$MODULE hole_3mm -Po 0 0 0 15 547491FA 00000000 ~~ -Li hole_3mm -Sc 0 -AR -Op 0 0 0 -T0 0 -2.54 1.5 1.5 0 0.3 N I 21 N "hole_3mm" -T1 0 3.175 1.5 1.5 0 0.3 N V 21 N "Val**" -DS 0 2.5 0 1.5 0.3 21 -DS -2.5 0 -1.5 0 0.3 21 -DS 2.5 0 1.5 0 0.3 21 -DS 0 -1.5 0 -2.5 0.3 21 -DC 0 0 2.5 0 0.3 21 -$PAD -Sh "" C 3 3 0 0 0 -Dr 3 0 0 -At STD N 0020FFFF -Ne 0 "" -Po 0 0 -$EndPAD -$EndMODULE hole_3mm -$EndLIBRARY diff --git a/Timelapse_keyboard/ld/devices.data b/Timelapse_keyboard/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/Timelapse_keyboard/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/Timelapse_keyboard/ld/stm32f103x4.ld b/Timelapse_keyboard/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/Timelapse_keyboard/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103x6.ld b/Timelapse_keyboard/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/Timelapse_keyboard/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103x8.ld b/Timelapse_keyboard/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/Timelapse_keyboard/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xB.ld b/Timelapse_keyboard/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/Timelapse_keyboard/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xC.ld b/Timelapse_keyboard/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/Timelapse_keyboard/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xD.ld b/Timelapse_keyboard/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/Timelapse_keyboard/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xE.ld b/Timelapse_keyboard/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/Timelapse_keyboard/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xF.ld b/Timelapse_keyboard/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/Timelapse_keyboard/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/ld/stm32f103xG.ld b/Timelapse_keyboard/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/Timelapse_keyboard/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard/main.c b/Timelapse_keyboard/main.c deleted file mode 100644 index 6986362..0000000 --- a/Timelapse_keyboard/main.c +++ /dev/null @@ -1,362 +0,0 @@ -/* - * main.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "usbkeybrd.h" -#include "hardware_ini.h" -#include "uart.h" -#include "GPS.h" -#ifdef ULTRASONIC -#include "ultrasonic.h" -#endif -#include "adc.h" -#include // independent watchdog - -volatile uint32_t Timer = 0; // global timer (milliseconds) -volatile uint32_t msctr = 0; // global milliseconds for different purposes -volatile int32_t systick_val = 0; -volatile int32_t timer_val = 0; -volatile int need_sync = 1; -volatile uint32_t last_corr_time = 0; // time of last PPS correction (seconds from midnight) - -// STK_CVR values for all milliseconds (RVR0) and last millisecond (RVR1) -volatile uint32_t RVR0 = STK_RVR_DEFAULT_VAL, RVR1 = STK_RVR_DEFAULT_VAL; - -curtime current_time = {25,61,61}; - -curtime trigger_time = {25, 61, 61}; -curtime adc_time[ADC_CHANNEL_NUMBER] = {{25, 61, 61}, {25, 61, 61}}; -#ifdef ULTRASONIC -curtime ultrasonic_time = {25, 61, 61}; -#endif -uint32_t trigger_ms = DIDNT_TRIGGERED, adc_ms[ADC_CHANNEL_NUMBER] = {DIDNT_TRIGGERED, DIDNT_TRIGGERED}; -#ifdef ULTRASONIC -uint32_t ultrasonic_ms = DIDNT_TRIGGERED; -#endif -void time_increment(){ - Timer = 0; - if(current_time.H == 25) return; // Time not initialized - if(++current_time.S == 60){ - current_time.S = 0; - if(++current_time.M == 60){ - current_time.M = 0; - if(++current_time.H == 24) - current_time.H = 0; - } - } -} - -int main(void){ - uint8_t *string; // string from UART2 & pointer to last full GPS answer - uint8_t lastGPSans[UART_BUF_DATA_SIZE] = {0}; - int i; - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - // init systick (1ms) - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(STK_RVR_DEFAULT_VAL); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); - - GPIO_init(); -/* - // if PC11 connected to usb 1.5kOhm pull-up through transistor - rcc_periph_clock_enable(RCC_GPIOC); - gpio_set(GPIOC, GPIO11); - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); -*/ - usb_disconnect(); // turn off USB while initializing all - usbkeybrd_setup(); - UART_init(USART2); // init GPS UART - #ifdef ULTRASONIC - tim2_init(); // ultrasonic timer - #endif - //tim4_init(); // beeper timer -/* - for (i = 0; i < 0x80000; i++) - __asm__("nop"); -*/ - usb_connect(); // turn on USB - GPS_send_start_seq(); - init_adc_sensor(); - // time (in milliseconds from MCU start) for trigger, adc & power LED status; power LED blink interval - // blink time: (1000ms - powerLEDblink) - LED ON - // GPSstatus_tm - timer for blinking by GPS LED if there's no GPS after timer is good - // powerLEDblink - LED blinking time (depends on power level) - uint32_t usbkbrdtm = 0, trigrtm = 0, powerLEDtm = 0, GPSstatus_tm = 0, powerLEDblink = 1; - // istriggered == 1 after ANY trigger's event (set it to 1 at start to prevent false events) - // GPSLEDblink - GPS LED blinking - uint8_t istriggered = 1, GPSLEDblink = 0; - iwdg_set_period_ms(50); // set watchdog timeout to 50ms - iwdg_start(); - while(1){ - if(Timer == 500) // turn off PPS LED after 500ms - gpio_set(LEDS_Y_PORT, LEDS_Y2_PIN); - poll_usbkeybrd(); - if(usbkbrdtm != msctr){ // process USB not frequently than once per 1ms - process_usbkbrd(); - usbkbrdtm = msctr; - } - #ifdef ULTRASONIC - poll_ultrasonic(); - #endif - poll_ADC(); - if((string = check_UART2())){ - memcpy(lastGPSans, string, UART_BUF_DATA_SIZE); - GPS_parse_answer(string); - } -/* -if(msctr - trigrtm > 3000){ - trigrtm = msctr; - for(i = 0; i < 3; ++i){ // IR or Laser - P("ADC"); - put_char_to_buf('0' + i); - P(" val: "); - print_int(ADC_value[i]); - newline(); - } -}*/ - if(istriggered){ // there was any trigger event - if(msctr - trigrtm > TRIGGER_DELAY || trigrtm > msctr){ // turn off LED & beeper - istriggered = 0; - gpio_set(LEDS_Y_PORT, LEDS_Y1_PIN); - gpio_set(BEEPER_PORT, BEEPER_PIN); - trigger_ms = DIDNT_TRIGGERED; - adc_ms[0] = DIDNT_TRIGGERED; - adc_ms[1] = DIDNT_TRIGGERED; - #ifdef ULTRASONIC - ultrasonic_ms = DIDNT_TRIGGERED; - #endif - } - }else{ - if(trigger_ms != DIDNT_TRIGGERED){ // Control Button pressed - trigrtm = msctr; - istriggered = 1; - P("Button time: "); - print_time(&trigger_time, trigger_ms); - if(*lastGPSans){ - P("GPS last message: "); - send_msg((char*)lastGPSans); - newline(); - } - } - for(i = 0; i < 2; ++i){ // IR or Laser - uint32_t adcms = adc_ms[i]; - if(adcms == DIDNT_TRIGGERED) continue; - int32_t timediff = Timer - adcms; - if(timediff < 0) timediff += 1000; - // pause for noice removal - if(timediff > ADC_NOICE_TIMEOUT && !istriggered){ - trigrtm = msctr; - istriggered = 1; - if(i == 0) P("Infrared"); - else P("Laser"); - /* P(" trig val: "); - print_int(ADC_trig_val[i]);*/ - put_char_to_buf(' '); - //P(" time: "); - print_time(&adc_time[i], adcms); - } - } - #ifdef ULTRASONIC - if(ultrasonic_ms != DIDNT_TRIGGERED && !istriggered){ - trigrtm = msctr; - istriggered = 1; - P("Ultrasonic time: "); - print_time(&ultrasonic_time, ultrasonic_ms); - } - #endif - if(istriggered){ // turn on Y1 LED - gpio_clear(LEDS_Y_PORT, LEDS_Y1_PIN); - //beep(); // turn on beeper - gpio_clear(BEEPER_PORT, BEEPER_PIN); - } - } - // check 12V power level (once per 1ms) - if(powerLEDtm != msctr){ - uint16_t _12V = ADC_value[2]; - if(_12V < GOOD_POWER_LEVEL){ // insufficient power? - blink LED R2 - // calculate blink time only if there's [was] too low level - if(_12V < POWER_ALRM_LEVEL || powerLEDblink){ - powerLEDblink = GOOD_POWER_LEVEL - _12V; - // critical level: power LED is almost OFF - if(_12V < POWER_CRITICAL_LEVEL) powerLEDblink = 990; - //if(powerLEDblink > 990) powerLEDblink = 990; // shadow LED not more than 0.99s - } - }else{ // power restored - LED R2 shines - if(powerLEDblink){ - gpio_clear(LEDS_R_PORT, LEDS_R2_PIN); - powerLEDblink = 0; - } - powerLEDtm = msctr; - } - if(powerLEDblink){ - if(GPIO_ODR(LEDS_R_PORT) & LEDS_R2_PIN){ // LED is OFF - if(msctr - powerLEDtm > powerLEDblink || msctr < powerLEDtm){ // turn LED ON - powerLEDtm = msctr; - gpio_clear(LEDS_R_PORT, LEDS_R2_PIN); - } - }else{ - if(msctr - powerLEDtm > (1000 - powerLEDblink) || msctr < powerLEDtm){ // turn LED OFF - powerLEDtm = msctr; - gpio_set(LEDS_R_PORT, LEDS_R2_PIN); - } - } - } - } - // check GPS status to turn on/off GPS LED - if(current_time.H < 24){ // timer OK - if((GPS_status != GPS_VALID) || need_sync){ - GPSLEDblink = 1; - }else{ - GPSLEDblink = 0; - if((GPIO_ODR(LEDS_G_PORT) & LEDS_G1_PIN) == 0) - gpio_clear(LEDS_G_PORT, LEDS_G1_PIN); // turn ON G1 LED - } - if(GPSLEDblink){ - if(msctr - GPSstatus_tm > 500 || msctr < GPSstatus_tm){ - GPSstatus_tm = msctr; - if(GPIO_ODR(LEDS_G_PORT) & LEDS_G1_PIN){ // LED is OFF - gpio_clear(LEDS_G_PORT, LEDS_G1_PIN); - }else{ - gpio_set(LEDS_G_PORT, LEDS_G1_PIN); - } - } - } - }else{ // something bad with timer - turn OFF G1 LED - if(!(GPIO_ODR(LEDS_G_PORT) & LEDS_G1_PIN)){ - gpio_set(LEDS_G_PORT, LEDS_G1_PIN); - } - } - iwdg_reset(); // reset watchdog - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - ++Timer; - ++msctr; - if(Timer == 999){ - STK_RVR = RVR1; - }else if(Timer == 1000){ - STK_RVR = RVR0; - time_increment(); - } -} -// STK_CVR - current systick val -// STK_RVR - ticks till interrupt - 1 - -// PA4 interrupt - PPS signal -void exti4_isr(){ - uint32_t t = 0, ticks; - static uint32_t ticksavr = 0, N = 0; - if(EXTI_PR & EXTI4){ - gpio_clear(LEDS_Y_PORT, LEDS_Y2_PIN); - // correct - systick_val = STK_CVR; - STK_CVR = RVR0; - timer_val = Timer; - Timer = 0; - systick_val = STK_RVR + 1 - systick_val; // Systick counts down! - if(timer_val < 10) timer_val += 1000; // our closks go faster than real - else if(timer_val < 990){ // something wrong - RVR0 = RVR1 = STK_RVR_DEFAULT_VAL; - STK_RVR = RVR0; - need_sync = 1; - goto theend; - }else - time_increment(); // ms counter less than 1000 - we need to increment time - t = current_time.H * 3600 + current_time.M * 60 + current_time.S; - if(t - last_corr_time == 1){ // PPS interval == 1s - ticks = systick_val + (timer_val-1)*(RVR0 + 1) + RVR1 + 1; - ++N; - ticksavr += ticks; - if(N > 20){ - ticks = ticksavr / N; - RVR0 = ticks / 1000 - 1; // main RVR value - STK_RVR = RVR0; - RVR1 = RVR0 + ticks % 1000; // last millisecond RVR value (with fine correction) - N = 0; - ticksavr = 0; - need_sync = 0; - } - }else{ - N = 0; - ticksavr = 0; - } - theend: - last_corr_time = t; - EXTI_PR = EXTI4; - } -} - -/** - * set current time by buffer hhmmss - */ -void set_time(uint8_t *buf){ - inline uint8_t atou(uint8_t *b){ - return (b[0]-'0')*10 + b[1]-'0'; - } - uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS; - if(H > 23) H -= 24; - current_time.H = H; - current_time.M = atou(&buf[2]); - current_time.S = atou(&buf[4]); -} - -/** - * print time: Tm - time structure, T - milliseconds - */ -void print_time(curtime *Tm, uint32_t T){ - int S = Tm->S, M = Tm->M, H = Tm->H; - if(H < 10) put_char_to_buf('0'); - print_int(H); put_char_to_buf(':'); - if(M < 10) put_char_to_buf('0'); - print_int(M); put_char_to_buf(':'); - if(S < 10) put_char_to_buf('0'); - print_int(S); put_char_to_buf('.'); - if(T < 100) put_char_to_buf('0'); - if(T < 10) put_char_to_buf('0'); - print_int(T); - P(", "); - S += H*3600 + M*60; - print_int(S); - put_char_to_buf('.'); - if(T < 100) put_char_to_buf('0'); - if(T < 10) put_char_to_buf('0'); - print_int(T); - if(GPS_status == GPS_NOT_VALID) P(" (not valid)"); - if(need_sync) P(" need synchronisation"); - newline(); -} -/* -void print_curtime(){ - uint32_t T = Timer; - if(current_time.H < 24 && GPS_status != GPS_WAIT){ - P("Current time: "); - print_time(¤t_time, T); - }else - P("Waiting for satellites\n"); -} -*/ diff --git a/Timelapse_keyboard/main.h b/Timelapse_keyboard/main.h deleted file mode 100644 index 6f17e29..0000000 --- a/Timelapse_keyboard/main.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -extern void *memcpy(void *dest, const void *src, int n); - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -#define STK_RVR_DEFAULT_VAL (8999) -#define TIMEZONE_GMT_PLUS (3) - -#define DIDNT_TRIGGERED (2000) - -// debounce delay: .5s -#define TRIGGER_DELAY (500) - -typedef struct{ - uint8_t H; - uint8_t M; - uint8_t S; -} curtime; - -extern curtime current_time; -extern volatile uint32_t Timer; // global timer (milliseconds) - -extern curtime trigger_time, adc_time[], ultrasonic_time; -extern uint32_t trigger_ms, adc_ms[], ultrasonic_ms; - -extern volatile int need_sync; - -void set_time(uint8_t *buf); - -void print_time(curtime *T, uint32_t m); -//void print_curtime(); - -#endif // __MAIN_H__ - diff --git a/Timelapse_keyboard/timelapse.bin b/Timelapse_keyboard/timelapse.bin deleted file mode 100755 index 80acb08..0000000 Binary files a/Timelapse_keyboard/timelapse.bin and /dev/null differ diff --git a/Timelapse_keyboard/uart.c b/Timelapse_keyboard/uart.c deleted file mode 100644 index ecaaab4..0000000 --- a/Timelapse_keyboard/uart.c +++ /dev/null @@ -1,247 +0,0 @@ -/* - * uart.c - functions to work with UART - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "uart.h" -#include "hardware_ini.h" - -// Buffers for Tx -static UART_buff TX_buffer[2]; // Tx buffers for all three ports -static UART_buff RX_buffer[2]; // Rx buffers for all three ports - -void fill_uart_RXbuff(uint32_t UART, uint8_t byte); - -/** - * Set UART speed - * @param lc - UART parameters or NULL for value from cdcacm.c (started - B115200,8,N,1) - */ -void UART_setspeed(uint32_t UART){ - usart_set_baudrate(UART, 9600); - usart_set_databits(UART, 8); - usart_set_stopbits(UART, USART_STOPBITS_1); - usart_set_parity(UART, USART_PARITY_NONE); - usart_set_flow_control(UART, USART_FLOWCONTROL_NONE); - usart_set_mode(UART, USART_MODE_TX_RX); -} - -/** - * Setup UART - */ -void UART_init(uint32_t UART){ - uint32_t irq, rcc, rccgpio, gpioport, gpiopin; - switch(UART){ - case USART2: // GPS UART - irq = NVIC_USART2_IRQ; // interrupt for given USART - rcc = RCC_USART2; // RCC timing of USART - rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output) - TX_buffer[1].end = 0; // reset counters - TX_buffer[1].start = 0; - RX_buffer[1].end = 0; - RX_buffer[1].start = 0; - // output pin setup - gpioport = GPIO_BANK_USART2_TX; - gpiopin = GPIO_USART2_TX; - break; - case USART1: - default: - irq = NVIC_USART1_IRQ; - rcc = RCC_USART1; - rccgpio = RCC_GPIOA; - TX_buffer[0].end = 0; - TX_buffer[0].start = 0; - RX_buffer[0].end = 0; - RX_buffer[0].start = 0; - gpioport = GPIO_BANK_USART1_TX; - gpiopin = GPIO_USART1_TX; - } - // enable clocking - rcc_periph_clock_enable(RCC_AFIO); // alternate functions - rcc_periph_clock_enable(rcc); // USART - rcc_periph_clock_enable(rccgpio); // GPIO pins - // enable output pin - gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin); - // enable IRQ - nvic_enable_irq(irq); - UART_setspeed(UART); - // Enable UART receive interrupt - USART_CR1(UART) |= USART_CR1_RXNEIE; - // Enable UART - usart_enable(UART); -} - -/* - * UART interrupts - */ -// common -void UART_isr(uint32_t UART){ - uint8_t bufidx = 0, data; - UART_buff *curbuff; - // Check if we were called because of RXNE - if(USART_SR(UART) & USART_SR_RXNE){ - // parse incoming byte - data = usart_recv(UART); - fill_uart_RXbuff(UART, data); - } - // Check if we were called because of TXE -> send next byte in buffer - if((USART_CR1(UART) & USART_CR1_TXEIE) && (USART_SR(UART) & USART_SR_TXE)){ - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - if(bufidx != curbuff->end){ // there's data in buffer - // Put data into the transmit register - usart_send(UART, curbuff->buf[bufidx]); - if(++(curbuff->start) == UART_BUF_DATA_SIZE){ // reload start - curbuff->start = 0; - } - }else{ // Disable the TXE interrupt, it's no longer needed - USART_CR1(UART) &= ~USART_CR1_TXEIE; - // empty indexes - curbuff->start = 0; - curbuff->end = 0; - } - } -} -// particular interrupt handlers -void usart1_isr(){ - UART_isr(USART1); -} -void usart2_isr(){ - UART_isr(USART2); -} - -// put byte into Tx buffer -void fill_uart_buff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx = 0, endidx; - if(!(USART_CR1(UART) & USART_CR1_UE)) return; // UART disabled - USART_CR1(UART) &= ~USART_CR1_TXEIE; // disable TX interrupt while buffer filling - while ((USART_SR(UART) & USART_SR_TXE) == 0); // wait until last byte send - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - endidx = curbuff->end; // end of data - curbuff->buf[endidx++] = byte; // put byte into buffer - // now check indexes - if(endidx != bufidx && endidx != UART_BUF_DATA_SIZE){ // all OK - there's enough place for data - (curbuff->end)++; // just increment index in buffer - }else{ // dangerous situation: possible overflow - if(endidx == UART_BUF_DATA_SIZE){ // end of buffer - if(bufidx != 0){ // no overflow - curbuff->end = 0; - goto end_of_fn; - } - } - // overflow: purge all data - bufidx = curbuff->start; // refresh data index - for(endidx = bufidx; endidx < UART_BUF_DATA_SIZE; endidx++) // first data porion - usart_send(UART, curbuff->buf[endidx]); - for(endidx = 0; endidx < bufidx; endidx++) // rest of data - usart_send(UART, curbuff->buf[endidx]); - curbuff->start = 0; - curbuff->end = 0; - return; - } - end_of_fn: - // enable interrupts to send data from buffer - USART_CR1(UART) |= USART_CR1_TXEIE; -} - -/** - * send data over UART - one function for each uart - * @param byte - one byte to put in UART queue - */ -void uart1_send(uint8_t byte){ - fill_uart_buff(USART1, byte); -} -void uart2_send(uint8_t byte){ - fill_uart_buff(USART2, byte); -} - - -/** - * Check whether UART2 have a full text line - * @return string with data if data ready or NULL - */ -uint8_t *check_UART2(){ - static int oldlen = 0; - static uint8_t buf[UART_BUF_DATA_SIZE+1]; - UART_buff *curbuff = &RX_buffer[1]; - uint8_t datalen = curbuff->end; // length of data in buffer - here we use param "end" - if(!datalen) return NULL; // buffer is empty - if(oldlen != datalen){ - if(curbuff->buf[curbuff->end-1] != '\n'){ // string not full - oldlen = datalen; - return NULL; - }else{ // full string - copy it to buffer & clear indexes - memcpy(buf, curbuff->buf, datalen); - buf[datalen] = 0; - oldlen = curbuff->end = 0; - return buf; - } - } - return NULL; -} - -/** - * Fill data in RX buffer to prepare it for further work - * we don't use "start" parameter here, it's 0 always - * @param UART - device to fill buffer - * @param byte - data byte - */ -void fill_uart_RXbuff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx; - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &RX_buffer[bufidx]; - if(curbuff->end == UART_BUF_DATA_SIZE){ // end of buffer - forget about data - curbuff->end = 0; - return; - } - curbuff->buf[curbuff->end++] = byte; // put byte into buffer -} diff --git a/Timelapse_keyboard/uart.h b/Timelapse_keyboard/uart.h deleted file mode 100644 index 85715ca..0000000 --- a/Timelapse_keyboard/uart.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * uart.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __UART_H__ -#define __UART_H__ - -// Size of buffers -#define UART_BUF_DATA_SIZE 128 - -typedef struct { - uint8_t buf[UART_BUF_DATA_SIZE]; - uint8_t start; // index from where to start reading - uint8_t end; // index from where to start writing -} UART_buff; - -void UART_init(uint32_t UART); -void UART_setspeed(uint32_t UART); - -void fill_uart_buff(uint32_t UART, uint8_t byte); -void uart1_send(uint8_t byte); -void uart2_send(uint8_t byte); - -uint8_t *check_UART2(); - -UART_buff *get_uart_buffer(uint32_t UART); - -#endif // __UART_H__ diff --git a/Timelapse_keyboard/ultrasonic.c b/Timelapse_keyboard/ultrasonic.c deleted file mode 100644 index 29b2386..0000000 --- a/Timelapse_keyboard/ultrasonic.c +++ /dev/null @@ -1,200 +0,0 @@ -/* - * ultrasonic.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#ifdef ULTRASONIC - -#include -#include -#include -#include - -#include "ultrasonic.h" -#include "usbkeybrd.h" -#include "main.h" - -static usmode US_mode = US_MODE_OFF; -static int overcapture = 0; - -#ifndef TIM_CCMR2_CC3S_IN_TI4 -#define TIM_CCMR2_CC3S_IN_TI4 (2) -#endif -#ifndef TIM_CCMR2_CC4S_IN_TI4 -#define TIM_CCMR2_CC4S_IN_TI4 (1 << 8) -#endif -/** - * Init timer 2 (&remap channels 3&4 to five-tolerant ports) - */ -void tim2_init(){ - // Turn off JTAG & SWD, remap TIM2_CH3/TIM2_CH4 to PB10/PB11 (five tolerant) - // don't forget about AFIO clock & PB clock! - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP2); - // setup PB10 & PB11 - // PB10 - Trig output - push/pull - gpio_set_mode(GPIO_BANK_TIM2_PR2_CH3, GPIO_MODE_OUTPUT_10_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_PR2_CH3); -// gpio_set_mode(GPIO_BANK_TIM2_CH3, GPIO_MODE_OUTPUT_10_MHZ, -// GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_CH3); - // PB11 - Echo input - floating -// gpio_set_mode(GPIO_BANK_TIM2_PR2_CH4, GPIO_MODE_INPUT, -// GPIO_CNF_INPUT_FLOAT, GPIO_TIM2_PR2_CH4); - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - // 36MHz of APB1 - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM2_PSC = 71; // prescaler is (div - 1) - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; -} - -/** - * Send Trig signal - * return 0 if another measurement still in process - */ -void start_ultrasonic(){ - overcapture = 0; - TIM2_CR1 = 0; - //TIM2_CR1 = TIM_CR1_URS; // Turn off timer to reconfigure, dusable UEV by UG set - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_DIER = 0; - TIM2_SR = 0; // clear all flags - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; - // PWM_OUT for TIM2_CH3 - TIM2_CCMR2 = TIM_CCMR2_CC3S_OUT | TIM_CCMR2_OC3M_PWM1; - // start measurement, active is high - TIM2_CCER = TIM_CCER_CC3E; - // enable CC3 IRQ - TIM2_DIER = TIM_DIER_CC3IE; - nvic_enable_irq(NVIC_TIM2_IRQ); - US_mode = US_MODE_TRIG; - // start timer in one-pulse mode without update event - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN | TIM_CR1_UDIS; -} - -/** - * Start measurement: - * TIM2_CH3 will capture high level & TIM2_CH4 will capture low - * The timer configured to 65536us to detect signal lost - */ -inline void run_measrmnt(){ - US_mode = US_MODE_WAIT; - TIM2_CR1 = 0; // Turn off timer to reconfigure - TIM2_DIER = 0; - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_SR = 0; // clear all flags - TIM2_ARR = MAX_MSRMNT_LEN; - // TIM2_CH3 & TIM2_CH4 configured as inputs, TIM2_CH3 connected to CH4 - TIM2_CCMR2 = TIM_CCMR2_CC3S_IN_TI4 | TIM_CCMR2_CC4S_IN_TI4; - // start - TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; - // enable interrupts CH3, CH4 & update - TIM2_DIER = TIM_DIER_CC3IE | TIM_DIER_CC4IE | TIM_DIER_UIE; - // start timer in one-pulse mode - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN; -} - -void tim2_isr(){ - // No signal - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - TIM2_SR = 0; - overcapture = 1; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - US_mode = US_MODE_READY; - } - // end of Trig pulse or start of measurements - if(TIM2_SR & TIM_SR_CC3IF){ // CCR ch3 interrupt - if(US_mode == US_MODE_TRIG){ // triggered - run measurement - run_measrmnt(); - }else if(US_mode == US_MODE_WAIT){ - US_mode = US_MODE_MEASUREMENT; - } - TIM2_SR &= ~TIM_SR_CC3IF; - } - if(TIM2_SR & TIM_SR_CC4IF){ - if(US_mode == US_MODE_MEASUREMENT){ - US_mode = US_MODE_READY; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - TIM2_CR1 = 0; // turn off timer - we don't need it more - } - TIM2_SR &= ~TIM_SR_CC3IF; - } -} - -/** - * Measure distance - * return 1 if measurements done - * set L to distance (in mm) or 0 in case of overcapture (no signal) - */ -int ultrasonic_get(uint32_t *L){ - uint32_t D; - if(US_mode != US_MODE_READY) - return 0; - US_mode = US_MODE_DONE; - if(!overcapture){ - D = ((uint32_t)(TIM2_CCR4 - TIM2_CCR3)) * 170; - *L = D / 1000; - }else *L = 0; - return 1; -} - -uint32_t last_us_val = 0; -void poll_ultrasonic(){ - uint32_t L; - if(US_mode == US_MODE_OFF){ - start_ultrasonic(); - return; - }//else if(ultrasonic_ms != DIDNT_TRIGGERED) return; - if(ultrasonic_get(&L)){ // measurements done, check event - if(!overcapture){ - if(!last_us_val){ - last_us_val = L; - }else{ - uint32_t diff = (last_us_val > L) ? last_us_val - L : L - last_us_val; - if(diff > MAX_LEN_DIFF){ - if(last_us_val > L){ // someone move in front of sensor - ultrasonic_ms = Timer; - memcpy(&ultrasonic_time, ¤t_time, sizeof(curtime)); - P("Pass! Was: "); - print_int(last_us_val); - P(", become: "); - print_int(L); - P("!!!\n"); - }else{ // free space - check for noices (signal should be at least 10ms) - diff = (ultrasonic_ms < Timer) ? Timer - ultrasonic_ms : ultrasonic_ms - Timer; - if(diff < ULTRASONIC_TIMEOUT) - ultrasonic_ms = DIDNT_TRIGGERED; - } - last_us_val = L; - } - } - } - start_ultrasonic(); - } -} - -#endif // ULTRASONIC diff --git a/Timelapse_keyboard/ultrasonic.h b/Timelapse_keyboard/ultrasonic.h deleted file mode 100644 index 6db4ee5..0000000 --- a/Timelapse_keyboard/ultrasonic.h +++ /dev/null @@ -1,55 +0,0 @@ -/* - * ultrasonic.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#ifdef ULTRASONIC - -#pragma once -#ifndef __ULTRASONIC_H__ -#define __ULTRASONIC_H__ - -#include - -void tim2_init(); -int ultrasonic_get(uint32_t *L); -void poll_ultrasonic(); -extern uint32_t last_us_val; - -// Sensor mode -typedef enum{ - US_MODE_OFF // sensor is off - ,US_MODE_DONE // measurement done, ready for next - ,US_MODE_TRIG // sensor triggered - ,US_MODE_WAIT // wait for pulse - ,US_MODE_MEASUREMENT // measurement in process - ,US_MODE_READY // measurements done -} usmode; - -// trigger time: after trigger event ends, timer will be configured for capture - 20us -#define TRIG_T (200) -// trigger length - 10us -#define TRIG_L (10) -// max length of measurement (to detect signal absence) -#define MAX_MSRMNT_LEN (65535) -// max difference of measured len for pass detection -#define MAX_LEN_DIFF (300) -// minimal length of signal in ms -#define ULTRASONIC_TIMEOUT (10) -#endif // __ULTRASONIC_H__ -#endif // ULTRASONIC diff --git a/Timelapse_keyboard/usbkeybrd.c b/Timelapse_keyboard/usbkeybrd.c deleted file mode 100644 index b5b7a77..0000000 --- a/Timelapse_keyboard/usbkeybrd.c +++ /dev/null @@ -1,276 +0,0 @@ -/* - * usbkeybrd.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "usbkeybrd.h" -#include "keycodes.h" - -#define BUFLEN (1024) -static char sendbuf[BUFLEN]; -static char *msg_start = sendbuf, *msg_end = sendbuf; -static const char *buf_end = sendbuf+BUFLEN; - -usbd_device *usbd_dev; - -const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = 0, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, -// 0x045E 0x005C - Microsoft Office Keyboard (106/109) - .idVendor = 0x045E, - .idProduct = 0x005C, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -static const uint8_t hid_report_descriptor[] = { - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x06, /* Usage (Keyboard) */ - 0xA1, 0x01, /* Collection (Application) */ -// 0x85, 0x02, /* Report ID */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0xE0, /* Usage Minimum (224) */ - 0x29, 0xE7, /* Usage Maximum (231) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (1) */ - 0x75, 0x01, /* Report Size (1) */ - 0x95, 0x08, /* Report Count (8) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (8) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x95, 0x05, /* Report Count (5) */ - 0x75, 0x01, /* Report Size (1) */ - 0x05, 0x08, /* Usage Page (Page# for LEDs) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x05, /* Usage Maximum (05) */ - 0x91, 0x02, /* Output (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x03, /* Report Size (3) */ - 0x91, 0x01, /* Output (Constant) */ - 0x95, 0x06, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (3) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x65, /* Logical Maximum (101) */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0x00, /* Usage Minimum (00) */ - 0x29, 0x65, /* Usage Maximum (101) */ - 0x81, 0x00, /* Input (Data, Array) */ - 0x09, 0x05, /* Usage (Vendor Defined) */ - 0x15, 0x00, /* Logical Minimum (0)) */ - 0x26, 0xFF, 0x00, /* Logical Maximum (255)) */ - 0x75, 0x08, /* Report Count (2)) */ - 0x95, 0x02, /* Report Size (8 bit)) */ - 0xB1, 0x02, /* Feature (Data, Variable, Absolute) */ - 0xC0 /* End Collection,End Collection */ -}; - -static const struct { - struct usb_hid_descriptor hid_descriptor; - struct { - uint8_t bReportDescriptorType; - uint16_t wDescriptorLength; - } __attribute__((packed)) hid_report; -} __attribute__((packed)) hid_function = { - .hid_descriptor = { - .bLength = sizeof(hid_function), - .bDescriptorType = USB_DT_HID, - .bcdHID = 0x0100, - .bCountryCode = 0, - .bNumDescriptors = 1, - }, - .hid_report = { - .bReportDescriptorType = USB_DT_REPORT, - .wDescriptorLength = sizeof(hid_report_descriptor), - }, -}; - -const struct usb_endpoint_descriptor hid_endpoint = { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x81, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 8, - .bInterval = 0x10, -}; - -const struct usb_interface_descriptor hid_iface = { - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_HID, - .bInterfaceSubClass = 1, // boot - .bInterfaceProtocol = 1, // keyboard - .iInterface = 0, - - .endpoint = &hid_endpoint, - - .extra = &hid_function, - .extralen = sizeof(hid_function), -}; - -const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = &hid_iface, -}}; - -const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 1, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0xC0, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Timelapse keyboard", - "EEV", - "v01", -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; -static int got_config = 0; -static int hid_control_request(usbd_device *usbddev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, - void (**complete)(usbd_device *usbddev, struct usb_setup_data *req)){ - (void)complete; - (void)usbddev; - - if ((req->bmRequestType != 0x81) || - (req->bRequest != USB_REQ_GET_DESCRIPTOR) || - (req->wValue != 0x2200)) - return 0; - - *buf = (uint8_t *)hid_report_descriptor; - *len = sizeof(hid_report_descriptor); - got_config = 1; - return 1; -} - -void hid_set_config(usbd_device *usbddev, uint16_t wValue){ - (void)wValue; - (void)usbddev; - usbd_ep_setup(usbd_dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL); - usbd_register_control_callback( - usbddev, - USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - hid_control_request); -} - -void usbkeybrd_setup(){ - usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - usbd_register_set_config_callback(usbd_dev, hid_set_config); -} - -void put_char_to_buf(char ch){ - *(msg_end++) = ch; - if(msg_end == buf_end) - msg_end = sendbuf; -} - -/** - * put data into keyboard buffer - * THERE's NO DATA CORRUPTION CONTROL HERE!!! - */ -void send_msg(char *msg){ - while(*msg){ - put_char_to_buf(*(msg++)); - } -} -/* -void newline(){ - put_char_to_buf('\n'); -}*/ - -/** - * send data from keyboard buffer - */ -void process_usbkbrd(){ - if(!got_config) return; // don't allow sending messages until first connection - to prevent hangs - static uint8_t pressed = 0; - if(pressed){ // the keyboard was "pressed" - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, release_key(), 8)) - pressed = 0; - }else if(msg_start != msg_end){ // we need to send keypress event - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, press_key(*msg_start), 8)){ - if(++msg_start == buf_end) - msg_start = sendbuf; - pressed = 1; - } - }else return; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - inline void putc(char c){ - if(c < 10) - put_char_to_buf(c + '0'); - else - put_char_to_buf(c + 'a' - 10); - } - put_char_to_buf('0'); - put_char_to_buf('x'); - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - char buf[10]; - int32_t L = 0; - if(N < 0){ - put_char_to_buf('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) put_char_to_buf(buf[L]); - }else put_char_to_buf('0'); -} - diff --git a/Timelapse_keyboard/usbkeybrd.h b/Timelapse_keyboard/usbkeybrd.h deleted file mode 100644 index ab3de8f..0000000 --- a/Timelapse_keyboard/usbkeybrd.h +++ /dev/null @@ -1,44 +0,0 @@ -/* - * usbkeybrd.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USBKEYBRD_H__ -#define __USBKEYBRD_H__ - -#include "main.h" - -extern usbd_device *usbd_dev; - -void process_usbkbrd(); -void send_msg(char *msg); -void put_char_to_buf(char ch); -#define P(x) send_msg(x) -void usbkeybrd_setup(); - -void print_hex(uint8_t *buff, uint8_t l); -void print_int(int32_t N); - -//void newline(); -#define newline() do{put_char_to_buf('\n');}while(0) - -#define poll_usbkeybrd() usbd_poll(usbd_dev) - -#endif // __USBKEYBRD_H__ diff --git a/Timelapse_keyboard_only_lasers/GPS.c b/Timelapse_keyboard_only_lasers/GPS.c deleted file mode 100644 index b684f42..0000000 --- a/Timelapse_keyboard_only_lasers/GPS.c +++ /dev/null @@ -1,162 +0,0 @@ -/* - * GPS.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "GPS.h" -#include "uart.h" - -#define GPS_endline() do{GPS_send_string((uint8_t*)"\r\n");}while(0) -#define U(arg) ((uint8_t*)arg) - -gps_status GPS_status = GPS_WAIT; - -void GPS_send_string(uint8_t *str){ - while(*str) - fill_uart_buff(USART2, *str++); -} - -int strncmp(const uint8_t *one, const uint8_t *two, int n){ - int diff = 0; - do{ - diff = (int)(*one++) - (int)(*two++); - }while(--n && diff == 0); - return diff; -} - -uint8_t *ustrchr(uint8_t *str, uint8_t symbol){ -// uint8_t *ptr = str; - do{ - if(*str == symbol) return str; - }while(*(++str)); - return NULL; -} - -uint8_t hex(uint8_t n){ - return ((n < 10) ? (n+'0') : (n+'A'-10)); -} - -/** - * Check checksum - */ -int checksum_true(uint8_t *buf){ - uint8_t *eol; - uint8_t checksum = 0, cs[3]; - if(*buf != '$' || !(eol = ustrchr(buf, '*'))){ - return 0; - } - while(++buf != eol) - checksum ^= *buf; - ++buf; - cs[0] = hex(checksum >> 4); - cs[1] = hex(checksum & 0x0f); - if(buf[0] == cs[0] && buf[1] == cs[1]) - return 1; - return 0; -} - -void send_chksum(uint8_t chs){ - fill_uart_buff(USART2, hex(chs >> 4)); - fill_uart_buff(USART2, hex(chs & 0x0f)); -} -/** - * Calculate checksum & write message to port - * @param buf - command to write (with leading $ and trailing *) - * return 0 if fails - */ -void write_with_checksum(uint8_t *buf){ - uint8_t checksum = 0; - GPS_send_string(buf); - ++buf; // skip leaders - do{ - checksum ^= *buf++; - }while(*buf && *buf != '*'); - send_chksum(checksum); - GPS_endline(); -} - -/** - * set rate for given NMEA field - * @param field - name of NMEA field - * @param rate - rate in seconds (0 disables field) - * @return -1 if fails, rate if OK - */ -void block_field(const uint8_t *field){ - uint8_t buf[22]; - memcpy(buf, U("$PUBX,40,"), 9); - memcpy(buf+9, field, 3); - memcpy(buf+12, U(",0,0,0,0*"), 9); - buf[21] = 0; - write_with_checksum(buf); -} - - -/** - * Send starting sequences (get only RMC messages) - */ -void GPS_send_start_seq(){ - const uint8_t *GPmsgs[5] = {U("GSV"), U("GSA"), U("GGA"), U("GLL"), U("VTG")}; - int i; - for(i = 0; i < 5; ++i) - block_field(GPmsgs[i]); -} - -/** - * Parse answer from GPS module - * - * Recommended minimum specific GPS/Transit data - * $GPRMC,hhmmss,status,latitude,N,longitude,E,spd,cog,ddmmyy,mv,mvE,mode*cs - * 1 = UTC of position fix - * 2 = Data status (V=navigation receiver warning) - * 3 = Latitude of fix - * 4 = N or S - * 5 = Longitude of fix - * 6 = E or W - * 7 = Speed over ground in knots - * 8 = Cource over ground in degrees - * 9 = UT date - * 10 = Magnetic variation degrees (Easterly var. subtracts from true course) - * 11 = E or W - * 12 = Mode: N(bad), E(approx), A(auto), D(diff) - * 213457.00,A,4340.59415,N,04127.47560,E,2.494,,290615,,,A*7B - */ -void GPS_parse_answer(uint8_t *buf){ - uint8_t *ptr; - if(strncmp(buf+3, U("RMC"), 3)){ // not RMC message - GPS_send_start_seq(); - return; - } - if(!checksum_true(buf)){ - return; // wrong checksum - } - buf += 7; // skip header - if(*buf == ','){ // time unknown - GPS_status = GPS_WAIT; - return; - } - ptr = ustrchr(buf, ','); - *ptr++ = 0; - if(*ptr == 'A'){ - GPS_status = GPS_VALID; - }else{ - GPS_status = GPS_NOT_VALID; - } - set_time(buf); -} diff --git a/Timelapse_keyboard_only_lasers/GPS.h b/Timelapse_keyboard_only_lasers/GPS.h deleted file mode 100644 index d400864..0000000 --- a/Timelapse_keyboard_only_lasers/GPS.h +++ /dev/null @@ -1,37 +0,0 @@ -/* - * GPS.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __GPS_H__ -#define __GPS_H__ - -typedef enum{ - GPS_WAIT // wait for satellites - ,GPS_NOT_VALID // time known, but not valid - ,GPS_VALID -} gps_status; - -extern gps_status GPS_status; - -void GPS_parse_answer(uint8_t *string); -void GPS_send_start_seq(); - -#endif // __GPS_H__ diff --git a/Timelapse_keyboard_only_lasers/Makefile b/Timelapse_keyboard_only_lasers/Makefile deleted file mode 100644 index 27c1b0a..0000000 --- a/Timelapse_keyboard_only_lasers/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = timelapse -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -# -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/Timelapse_keyboard_only_lasers/Readme.md b/Timelapse_keyboard_only_lasers/Readme.md deleted file mode 100644 index 8fe3a80..0000000 --- a/Timelapse_keyboard_only_lasers/Readme.md +++ /dev/null @@ -1,41 +0,0 @@ -## Time-lapse as USB HID keyboard - -This tool allow to get precision time of events: four lasers with sensors (0->1 event), pressing switch-button (1->0 event). - -Just connect board to any device with USB keyboard support, after some time -(needed to establish GPS connection and precision timer setup) it will simulate -keyboard on which somebody types time of sensors' state changing - - -#### Sensors supprorted -* four lasers or other things, catch signal 0->1 -* simple switch-button, catch signal 0->1 - -To get precision time this tool use GPS module (NEO-6M) - -#### Connection diagram -| *Pin* | *Function* | -| :---: | :-------- | -| PA0 | Laser 1 | -| PA1 | Laser 2 | -| PA2 | GPS Rx (MCU Tx) | -| PA3 | GPS Tx (MCU Rx) | -| PA4 | GPS PPS signal | -| PA5 | Trigger (button) switch | -| PA6 | Input power measurement | -| PA7 | Laser 3 | -| PA8 | Laser 4 | -| PB9 | Beeper | -| * LEDS * | -| PA13 | Yellow LED1 - Laser1/4 found | -| PA15 | Yellow LED2 - PPS event | -| PB7 | Green LED1 - Laser3 found | -| PB8 | Green LED2 - power state: ON == 12V OK, BLINK == insufficient power | -| PB6 | Red LED1 - Laser2 found | -| PB7 | Red LED2 - GPS state: OFF == not ready, BLINK == need sync, ON == ready | - - -#### Powering devices -* To power up GPS module you can use +5V or +3.3V. -* Lasers & photosensors need 10..30V of power, I connect them to 12V -* Lasers' sensors connected to MCU through optocouples diff --git a/Timelapse_keyboard_only_lasers/adc.c b/Timelapse_keyboard_only_lasers/adc.c deleted file mode 100644 index f8de5f6..0000000 --- a/Timelapse_keyboard_only_lasers/adc.c +++ /dev/null @@ -1,62 +0,0 @@ -/* - * adc.c - functions for Sharp 2Y0A02 distance meter & photosensor - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "adc.h" -#include "main.h" -#include "usbkeybrd.h" - -uint16_t ADC_value; // Value of ADC -uint16_t ADC_trig_val; // -//- at trigger time - -void init_adc_sensor(){ - // we will use ADC1 channel 0 for IR sensor & ADC1 channel 1 for laser's photoresistor - // Make sure the ADC doesn't run during config - adc_off(ADC1); - // enable ADC & PA0/PA1 clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN | RCC_APB2ENR_IOPAEN); - rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4); - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO6); - rcc_periph_clock_enable(RCC_DMA1); // enable DMA for ADC values storing - // Configure ADC as continuous scan mode with DMA - ADC1_CR1 = ADC_CR1_SCAN; // enable scan mode - // set sample time on channels 1&2: 239.5 cycles for better results - ADC1_SMPR2 = 0x3f; - dma_channel_reset(DMA1, DMA_CHANNEL1); - DMA1_CPAR1 = (uint32_t) &(ADC_DR(ADC1)); - DMA1_CMAR1 = (uint32_t) &ADC_value; - DMA1_CNDTR1 = 1; - DMA1_CCR1 = DMA_CCR_MINC | DMA_CCR_PSIZE_16BIT | DMA_CCR_MSIZE_16BIT - | DMA_CCR_CIRC | DMA_CCR_PL_HIGH | DMA_CCR_EN; - // continuous conv, enable ADC & DMA - ADC1_CR2 = ADC_CR2_CONT | ADC_CR2_ADON | ADC_CR2_DMA; - // set channels - uint8_t adc_channel_array = ADC_POWER_CHANNEL; - adc_set_regular_sequence(ADC1, 1, &adc_channel_array); - // reset calibration registers & start calibration - ADC1_CR2 |= ADC_CR2_RSTCAL; - while(ADC1_CR2 & ADC_CR2_RSTCAL); // wait for registers reset - ADC1_CR2 |= ADC_CR2_CAL; - while(ADC1_CR2 & ADC_CR2_CAL); // wait for calibration ends - nvic_enable_irq(NVIC_ADC1_2_IRQ); - ADC1_CR2 |= ADC_CR2_SWSTART; - // turn on ADC - to do it we need set ADC_CR2_ADON again! - ADC1_CR2 |= ADC_CR2_ADON; -} diff --git a/Timelapse_keyboard_only_lasers/adc.h b/Timelapse_keyboard_only_lasers/adc.h deleted file mode 100644 index 558aaca..0000000 --- a/Timelapse_keyboard_only_lasers/adc.h +++ /dev/null @@ -1,45 +0,0 @@ -/* - * adc.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SHARP_H__ -#define __SHARP_H__ - -#include - -extern uint16_t ADC_value; - -// pause for noice removal -#define ADC_NOICE_TIMEOUT (5) - -// channel6 - 12V -#define ADC_POWER_CHANNEL (6) -// 10.8V - power alarm (resistor divider: 10kOhm : (3.0kOhm || zener), U/100=2/5*ADC_value) -// (11.15Vin == 2.25Vout) -#define POWER_ALRM_LEVEL (2705) -// critical voltage: approx 8V -#define POWER_CRITICAL_LEVEL (2000) -// 11.5V - power OK -#define GOOD_POWER_LEVEL (2880) - -void init_adc_sensor(); - -#endif // __SHARP_H__ diff --git a/Timelapse_keyboard_only_lasers/hardware_ini.c b/Timelapse_keyboard_only_lasers/hardware_ini.c deleted file mode 100644 index 2458fa2..0000000 --- a/Timelapse_keyboard_only_lasers/hardware_ini.c +++ /dev/null @@ -1,129 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" -#include - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - // enable clocking for all ports, APB2 & AFIO (we need AFIO to remap JTAG pins) - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN | RCC_APB2ENR_AFIOEN); - // turn off SWJ/JTAG - AFIO_MAPR = AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF; - /* - * Setup EXTI on PA4 (PPS input from GPS) - pull down - * EXTI on PA5 - also pull down (trigger for time measurement) - */ - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO0 | GPIO1 | GPIO4 | GPIO5 | GPIO7 | GPIO8); - // PA0/1 and PA7/8 - Lasers - //gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO0 | GPIO1); - //gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO0 | GPIO1); - // EXTI0 - Laser1, EXTI1 - Laser2, EXTI4 - PPS, EXTI5 - Button, EXTI7 - Laser3, EXTI8 - Laser4 - // trigger on rising edge - exti_set_trigger(EXTI0 | EXTI1 | EXTI4 | EXTI5 | EXTI7 | EXTI8, EXTI_TRIGGER_RISING); - AFIO_EXTICR1 = 0; // EXTI 0-3 from PORTA - nvic_enable_irq(NVIC_EXTI4_IRQ); // PPS - nvic_enable_irq(NVIC_EXTI0_IRQ); // Laser1 - nvic_enable_irq(NVIC_EXTI1_IRQ); // Laser2 - nvic_enable_irq(NVIC_EXTI9_5_IRQ); // Button, Lasers 3/4 - exti_enable_request(EXTI0 | EXTI1 | EXTI4 | EXTI5 | EXTI7 | EXTI8); - // LEDS: opendrain output (&turn all OFF) - gpio_set(LEDS_Y_PORT, LEDS_Y1_PIN | LEDS_Y2_PIN); - gpio_set_mode(LEDS_Y_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_Y1_PIN | LEDS_Y2_PIN); - gpio_set(LEDS_G_PORT, LEDS_G1_PIN | LEDS_G2_PIN); - gpio_set_mode(LEDS_G_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_G1_PIN | LEDS_G2_PIN); - gpio_set(LEDS_R_PORT, LEDS_R1_PIN | LEDS_R2_PIN); - gpio_set_mode(LEDS_R_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LEDS_R1_PIN | LEDS_R2_PIN); - // beeper pin: push-pull - gpio_set(BEEPER_PORT, BEEPER_PIN); - gpio_set_mode(BEEPER_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, BEEPER_PIN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/** - * PA5 interrupt - print time at button-switch trigger and Lasers3/4 - * EXTI5 - Button, EXTI7 - Laser3, EXTI8 - Laser4 - */ -void exti9_5_isr(){ - if(EXTI_PR & EXTI5){ - if(trigger_ms[0] == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms[0] = Timer; - memcpy(&trigger_time[0], ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI5; - } - if(EXTI_PR & EXTI7){ - if(trigger_ms[3] == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms[3] = Timer; - memcpy(&trigger_time[3], ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI7; - } - if(EXTI_PR & EXTI8){ - if(trigger_ms[4] == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms[4] = Timer; - memcpy(&trigger_time[4], ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI8; - } -} - -void exti0_isr(){ // Laser1 - if(EXTI_PR & EXTI0){ - if(trigger_ms[1] == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms[1] = Timer; - memcpy(&trigger_time[1], ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI0; - } -} - -void exti1_isr(){ // Laser2 -// if(EXTI_PR & EXTI1){ - if(trigger_ms[2] == DIDNT_TRIGGERED){ // prevent bounce - trigger_ms[2] = Timer; - memcpy(&trigger_time[2], ¤t_time, sizeof(curtime)); - } - EXTI_PR = EXTI1; - //} -} diff --git a/Timelapse_keyboard_only_lasers/hardware_ini.h b/Timelapse_keyboard_only_lasers/hardware_ini.h deleted file mode 100644 index 7ca578f..0000000 --- a/Timelapse_keyboard_only_lasers/hardware_ini.h +++ /dev/null @@ -1,75 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - -void GPIO_init(); -void SysTick_init(); - -// yellow LEDs: PA11, PA12; Y1 - trigr, Y2 - PPS -#define LEDS_Y_PORT GPIOA -#define LEDS_Y1_PIN GPIO13 -#define LEDS_Y2_PIN GPIO15 -// green LEDs: PB7, PB8; G1 - GPS rdy -#define LEDS_G_PORT GPIOB -#define LEDS_G1_PIN GPIO7 -#define LEDS_G2_PIN GPIO8 -// red LEDs: PB6, PB5; R2 - power -#define LEDS_R_PORT GPIOB -#define LEDS_R1_PIN GPIO6 -#define LEDS_R2_PIN GPIO5 -// beeper - PB9 -#define BEEPER_PORT GPIOB -#define BEEPER_PIN GPIO9 - - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - - -#endif // __HARDWARE_INI_H__ diff --git a/Timelapse_keyboard_only_lasers/keycodes.c b/Timelapse_keyboard_only_lasers/keycodes.c deleted file mode 100644 index 7d9d2f5..0000000 --- a/Timelapse_keyboard_only_lasers/keycodes.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * keycodes.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "keycodes.h" -/* - * Keyboard buffer: - * buf[0]: MOD - * buf[1]: reserved - * buf[2]..buf[7] - keycodes 1..6 - */ -static uint8_t buf[8] = {0,0,0,0,0,0,0,0}; - -#define _(x) (x|0x80) -// array for keycodes according to ASCII table; MSB is MOD_SHIFT flag -static const uint8_t keycodes[] = { - // space !"#$%&' - KEY_SPACE, _(KEY_1), _(KEY_QUOTE), _(KEY_3), _(KEY_4), _(KEY_5), _(KEY_7), KEY_QUOTE, - // ()*+,-./ - _(KEY_9), _(KEY_0), _(KEY_8), _(KEY_EQUAL), KEY_COMMA, KEY_MINUS, KEY_PERIOD, KEY_SLASH, - // 0..9 - 39, 30, 31, 32, 33, 34, 35, 36, 37, 38, - // :;<=>?@ - _(KEY_SEMICOLON), KEY_SEMICOLON, _(KEY_COMMA), KEY_EQUAL, _(KEY_PERIOD), _(KEY_SLASH), _(KEY_2), - // A..Z: for a in $(seq 0 25); do printf "$((a+132)),"; done - 132,133,134,135,136,137,138,139,140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157, - // [\]^_` - KEY_LEFT_BRACE, KEY_BACKSLASH, KEY_RIGHT_BRACE, _(KEY_6), _(KEY_MINUS), KEY_TILDE, - // a..z: for a in $(seq 0 25); do printf "$((a+4)),"; done - 4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29, - // {|}~ - _(KEY_LEFT_BRACE), _(KEY_BACKSLASH), _(KEY_RIGHT_BRACE), _(KEY_TILDE) -}; - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY){ - buf[0] = MOD; - buf[2] = KEY; - return buf; -} - -/** - * return buffer for sending symbol "ltr" with addition modificator mod - */ -uint8_t *press_key_mod(char ltr, uint8_t mod){ - uint8_t MOD = 0; - uint8_t KEY = 0; - if(ltr > 31){ - KEY = keycodes[ltr - 32]; - if(KEY & 0x80){ - MOD = MOD_SHIFT; - KEY &= 0x7f; - } - }else if (ltr == '\n') KEY = KEY_ENTER; - buf[0] = MOD | mod; - buf[2] = KEY; - return buf; -} diff --git a/Timelapse_keyboard_only_lasers/keycodes.h b/Timelapse_keyboard_only_lasers/keycodes.h deleted file mode 100644 index 98a2fa1..0000000 --- a/Timelapse_keyboard_only_lasers/keycodes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* - * keycodes.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __KEYKODES_H__ -#define __KEYKODES_H__ - -#include - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY); -#define release_key() set_key_buf(0,0) -uint8_t *press_key_mod(char key, uint8_t mod); -#define press_key(k) press_key_mod(k, 0) - -#define MOD_CTRL 0x01 -#define MOD_SHIFT 0x02 -#define MOD_ALT 0x04 -#define MOD_GUI 0x08 - -#define LEFT(mod) (mod) -#define RIGHT(mod) ((mod << 4)) - -#define KEY_A 4 -#define KEY_B 5 -#define KEY_C 6 -#define KEY_D 7 -#define KEY_E 8 -#define KEY_F 9 -#define KEY_G 10 -#define KEY_H 11 -#define KEY_I 12 -#define KEY_J 13 -#define KEY_K 14 -#define KEY_L 15 -#define KEY_M 16 -#define KEY_N 17 -#define KEY_O 18 -#define KEY_P 19 -#define KEY_Q 20 -#define KEY_R 21 -#define KEY_S 22 -#define KEY_T 23 -#define KEY_U 24 -#define KEY_V 25 -#define KEY_W 26 -#define KEY_X 27 -#define KEY_Y 28 -#define KEY_Z 29 -#define KEY_1 30 -#define KEY_2 31 -#define KEY_3 32 -#define KEY_4 33 -#define KEY_5 34 -#define KEY_6 35 -#define KEY_7 36 -#define KEY_8 37 -#define KEY_9 38 -#define KEY_0 39 -#define KEY_ENTER 40 -#define KEY_ESC 41 -#define KEY_BACKSPACE 42 -#define KEY_TAB 43 -#define KEY_SPACE 44 -#define KEY_MINUS 45 -#define KEY_EQUAL 46 -#define KEY_LEFT_BRACE 47 -#define KEY_RIGHT_BRACE 48 -#define KEY_BACKSLASH 49 -#define KEY_NUMBER 50 -#define KEY_SEMICOLON 51 -#define KEY_QUOTE 52 -#define KEY_TILDE 53 -#define KEY_COMMA 54 -#define KEY_PERIOD 55 -#define KEY_SLASH 56 -#define KEY_CAPS_LOCK 57 -#define KEY_F1 58 -#define KEY_F2 59 -#define KEY_F3 60 -#define KEY_F4 61 -#define KEY_F5 62 -#define KEY_F6 63 -#define KEY_F7 64 -#define KEY_F8 65 -#define KEY_F9 66 -#define KEY_F10 67 -#define KEY_F11 68 -#define KEY_F12 69 -#define KEY_PRINTSCREEN 70 -#define KEY_SCROLL_LOCK 71 -#define KEY_PAUSE 72 -#define KEY_INSERT 73 -#define KEY_HOME 74 -#define KEY_PAGE_UP 75 -#define KEY_DELETE 76 -#define KEY_END 77 -#define KEY_PAGE_DOWN 78 -#define KEY_RIGHT 79 -#define KEY_LEFT 80 -#define KEY_DOWN 81 -#define KEY_UP 82 -#define KEY_NUM_LOCK 83 -#define KEYPAD_SLASH 84 -#define KEYPAD_ASTERIX 85 -#define KEYPAD_MINUS 86 -#define KEYPAD_PLUS 87 -#define KEYPAD_ENTER 88 -#define KEYPAD_1 89 -#define KEYPAD_2 90 -#define KEYPAD_3 91 -#define KEYPAD_4 92 -#define KEYPAD_5 93 -#define KEYPAD_6 94 -#define KEYPAD_7 95 -#define KEYPAD_8 96 -#define KEYPAD_9 97 -#define KEYPAD_0 98 -#define KEYPAD_PERIOD 99 - -#endif // __KEYKODES_H__ diff --git a/Timelapse_keyboard_only_lasers/ld/devices.data b/Timelapse_keyboard_only_lasers/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/Timelapse_keyboard_only_lasers/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103x4.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103x6.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103x8.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xB.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xC.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xD.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xE.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xF.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/ld/stm32f103xG.ld b/Timelapse_keyboard_only_lasers/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/Timelapse_keyboard_only_lasers/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/Timelapse_keyboard_only_lasers/main.c b/Timelapse_keyboard_only_lasers/main.c deleted file mode 100644 index b656100..0000000 --- a/Timelapse_keyboard_only_lasers/main.c +++ /dev/null @@ -1,311 +0,0 @@ -/* - * main.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "usbkeybrd.h" -#include "hardware_ini.h" -#include "uart.h" -#include "GPS.h" -#include "adc.h" -#include // independent watchdog - -volatile uint32_t Timer = 0; // global timer (milliseconds) -volatile uint32_t msctr = 0; // global milliseconds for different purposes -volatile int32_t systick_val = 0; -volatile int32_t timer_val = 0; -volatile int need_sync = 1; -volatile uint32_t last_corr_time = 0; // time of last PPS correction (seconds from midnight) - -// STK_CVR values for all milliseconds (RVR0) and last millisecond (RVR1) -volatile uint32_t RVR0 = STK_RVR_DEFAULT_VAL, RVR1 = STK_RVR_DEFAULT_VAL; - -#define TMNOTINI {25,61,61} -curtime current_time = TMNOTINI; - -// 0 - Button, 1..4 - Lasers1..4 -curtime trigger_time[5] = {TMNOTINI, TMNOTINI, TMNOTINI, TMNOTINI, TMNOTINI}; -uint32_t trigger_ms[5] = {DIDNT_TRIGGERED, DIDNT_TRIGGERED, DIDNT_TRIGGERED, DIDNT_TRIGGERED, DIDNT_TRIGGERED}; - -void time_increment(){ - Timer = 0; - if(current_time.H == 25) return; // Time not initialized - if(++current_time.S == 60){ - current_time.S = 0; - if(++current_time.M == 60){ - current_time.M = 0; - if(++current_time.H == 24) - current_time.H = 0; - } - } -} - -int main(void){ - uint8_t *string; // string from UART2 & pointer to last full GPS answer - uint8_t lastGPSans[UART_BUF_DATA_SIZE] = {0}; - int i; - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - // init systick (1ms) - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(STK_RVR_DEFAULT_VAL); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); - - GPIO_init(); -/* - // if PC11 connected to usb 1.5kOhm pull-up through transistor - rcc_periph_clock_enable(RCC_GPIOC); - gpio_set(GPIOC, GPIO11); - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); -*/ - usb_disconnect(); // turn off USB while initializing all - usbkeybrd_setup(); - UART_init(USART2); // init GPS UART - - usb_connect(); // turn on USB - GPS_send_start_seq(); - init_adc_sensor(); - // time (in milliseconds from MCU start) for trigger, adc & power LED status; power LED blink interval - // blink time: (1000ms - powerLEDblink) - LED ON - // GPSstatus_tm - timer for blinking by GPS LED if there's no GPS after timer is good - // powerLEDblink - LED blinking time (depends on power level) - uint32_t usbkbrdtm = 0, trigrtm = 0, powerLEDtm = 0, GPSstatus_tm = 0, powerLEDblink = 1; - // istriggered == 1 after ANY trigger's event (set it to 1 at start to prevent false events) - // GPSLEDblink - GPS LED blinking - uint8_t istriggered = 1, GPSLEDblink = 0; - iwdg_set_period_ms(50); // set watchdog timeout to 50ms - iwdg_start(); - while(1){ - if(Timer == 500) // turn off PPS LED after 500ms - gpio_set(LEDS_Y_PORT, LEDS_Y2_PIN); - poll_usbkeybrd(); - if(usbkbrdtm != msctr){ // process USB not frequently than once per 1ms - process_usbkbrd(); - usbkbrdtm = msctr; - } - if((string = check_UART2())){ - memcpy(lastGPSans, string, UART_BUF_DATA_SIZE); - GPS_parse_answer(string); - } - if(GPIO_ODR(GPIOA) & GPIO0 || GPIO_ODR(GPIOA) & GPIO8 ){ // Laser 1/4 shines - gpio_clear(LEDS_Y_PORT, LEDS_Y1_PIN); - }else{ - gpio_set(LEDS_Y_PORT, LEDS_Y1_PIN); - } - if(GPIO_ODR(GPIOA) & GPIO1){ // Laser 2 shines - gpio_clear(LEDS_R_PORT, LEDS_R1_PIN); - }else{ - gpio_set(LEDS_R_PORT, LEDS_R1_PIN); - } - if(GPIO_ODR(GPIOA) & GPIO7){ // Laser 3 shines - gpio_clear(LEDS_G_PORT, LEDS_G1_PIN); - }else{ - gpio_set(LEDS_G_PORT, LEDS_G1_PIN); - } - if(istriggered){ // there was any trigger event - if(msctr - trigrtm > TRIGGER_DELAY || trigrtm > msctr){ // turn off LED & beeper - istriggered = 0; - gpio_set(BEEPER_PORT, BEEPER_PIN); - for(i = 0; i < 5; ++i){ - if(trigger_ms[i] != DIDNT_TRIGGERED){ // show all messages - P("Event"); - put_char_to_buf('0' + i); - P(" time: "); - print_time(&(trigger_time[i]), trigger_ms[i]); - trigger_ms[i] = DIDNT_TRIGGERED; - } - } - } - }else{ - for(i = 0; i < 5; ++i){ - if(trigger_ms[i] != DIDNT_TRIGGERED){ // Control Button pressed or Lasers shadows - trigrtm = msctr; - istriggered = 1; - /*if(*lastGPSans){ - P("GPS last message: "); - send_msg((char*)lastGPSans); - newline(); - }*/ - } - } - if(istriggered){ // turn on beeper - gpio_clear(BEEPER_PORT, BEEPER_PIN); - } - } - // check 12V power level (once per 1ms) - if(powerLEDtm != msctr){ - uint16_t _12V = ADC_value; - if(_12V < GOOD_POWER_LEVEL){ // insufficient power? - blink LED R2 - // calculate blink time only if there's [was] too low level - if(_12V < POWER_ALRM_LEVEL || powerLEDblink){ - powerLEDblink = GOOD_POWER_LEVEL - _12V; - // critical level: power LED is almost OFF - if(_12V < POWER_CRITICAL_LEVEL) powerLEDblink = 990; - } - }else{ // power restored - LED G2 shines - if(powerLEDblink){ - gpio_clear(LEDS_G_PORT, LEDS_G2_PIN); - powerLEDblink = 0; - } - powerLEDtm = msctr; - } - if(powerLEDblink){ - if(GPIO_ODR(LEDS_G_PORT) & LEDS_G2_PIN){ // LED is OFF - if(msctr - powerLEDtm > powerLEDblink || msctr < powerLEDtm){ // turn LED ON - powerLEDtm = msctr; - gpio_clear(LEDS_G_PORT, LEDS_G2_PIN); - } - }else{ - if(msctr - powerLEDtm > (1000 - powerLEDblink) || msctr < powerLEDtm){ // turn LED OFF - powerLEDtm = msctr; - gpio_set(LEDS_G_PORT, LEDS_G2_PIN); - } - } - } - } - // check GPS status to turn on/off GPS LED - if(current_time.H < 24){ // timer OK - if((GPS_status != GPS_VALID) || need_sync){ - GPSLEDblink = 1; - }else{ - GPSLEDblink = 0; - if((GPIO_ODR(LEDS_R_PORT) & LEDS_R2_PIN) == 0) - gpio_clear(LEDS_R_PORT, LEDS_R2_PIN); // turn ON R2 LED - } - if(GPSLEDblink){ - if(msctr - GPSstatus_tm > 500 || msctr < GPSstatus_tm){ - GPSstatus_tm = msctr; - if(GPIO_ODR(LEDS_R_PORT) & LEDS_R2_PIN){ // LED is OFF - gpio_clear(LEDS_R_PORT, LEDS_R2_PIN); - }else{ - gpio_set(LEDS_R_PORT, LEDS_R2_PIN); - } - } - } - }else{ // something bad with timer - turn OFF R2 LED - if(!(GPIO_ODR(LEDS_R_PORT) & LEDS_R2_PIN)){ - gpio_set(LEDS_R_PORT, LEDS_R2_PIN); - } - } - iwdg_reset(); // reset watchdog - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - ++Timer; - ++msctr; - if(Timer == 999){ - STK_RVR = RVR1; - }else if(Timer == 1000){ - STK_RVR = RVR0; - time_increment(); - } -} -// STK_CVR - current systick val -// STK_RVR - ticks till interrupt - 1 - -// PA4 interrupt - PPS signal -void exti4_isr(){ - uint32_t t = 0, ticks; - static uint32_t ticksavr = 0, N = 0; - if(EXTI_PR & EXTI4){ - gpio_clear(LEDS_Y_PORT, LEDS_Y2_PIN); - // correct - systick_val = STK_CVR; - STK_CVR = RVR0; - timer_val = Timer; - Timer = 0; - systick_val = STK_RVR + 1 - systick_val; // Systick counts down! - if(timer_val < 10) timer_val += 1000; // our closks go faster than real - else if(timer_val < 990){ // something wrong - RVR0 = RVR1 = STK_RVR_DEFAULT_VAL; - STK_RVR = RVR0; - need_sync = 1; - goto theend; - }else - time_increment(); // ms counter less than 1000 - we need to increment time - t = current_time.H * 3600 + current_time.M * 60 + current_time.S; - if(t - last_corr_time == 1){ // PPS interval == 1s - ticks = systick_val + (timer_val-1)*(RVR0 + 1) + RVR1 + 1; - ++N; - ticksavr += ticks; - if(N > 20){ - ticks = ticksavr / N; - RVR0 = ticks / 1000 - 1; // main RVR value - STK_RVR = RVR0; - RVR1 = RVR0 + ticks % 1000; // last millisecond RVR value (with fine correction) - N = 0; - ticksavr = 0; - need_sync = 0; - } - }else{ - N = 0; - ticksavr = 0; - } - theend: - last_corr_time = t; - EXTI_PR = EXTI4; - } -} - -/** - * set current time by buffer hhmmss - */ -void set_time(uint8_t *buf){ - inline uint8_t atou(uint8_t *b){ - return (b[0]-'0')*10 + b[1]-'0'; - } - uint8_t H = atou(buf) + TIMEZONE_GMT_PLUS; - if(H > 23) H -= 24; - current_time.H = H; - current_time.M = atou(&buf[2]); - current_time.S = atou(&buf[4]); -} - -/** - * print time: Tm - time structure, T - milliseconds - */ -void print_time(curtime *Tm, uint32_t T){ - int S = Tm->S, M = Tm->M, H = Tm->H; - if(H < 10) put_char_to_buf('0'); - print_int(H); put_char_to_buf(':'); - if(M < 10) put_char_to_buf('0'); - print_int(M); put_char_to_buf(':'); - if(S < 10) put_char_to_buf('0'); - print_int(S); put_char_to_buf('.'); - if(T < 100) put_char_to_buf('0'); - if(T < 10) put_char_to_buf('0'); - print_int(T); - P(", "); - S += H*3600 + M*60; - print_int(S); - put_char_to_buf('.'); - if(T < 100) put_char_to_buf('0'); - if(T < 10) put_char_to_buf('0'); - print_int(T); - if(GPS_status == GPS_NOT_VALID) P(" (not valid)"); - if(need_sync) P(" need synchronisation"); - newline(); -} diff --git a/Timelapse_keyboard_only_lasers/main.h b/Timelapse_keyboard_only_lasers/main.h deleted file mode 100644 index 1565652..0000000 --- a/Timelapse_keyboard_only_lasers/main.h +++ /dev/null @@ -1,75 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -extern void *memcpy(void *dest, const void *src, int n); - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -#define STK_RVR_DEFAULT_VAL (8999) -#define TIMEZONE_GMT_PLUS (3) - -#define DIDNT_TRIGGERED (2000) - -// debounce delay: .4s -#define TRIGGER_DELAY (400) - -typedef struct{ - uint8_t H; - uint8_t M; - uint8_t S; -} curtime; - -extern curtime current_time; -extern volatile uint32_t Timer; // global timer (milliseconds) - -extern curtime trigger_time[]; -extern uint32_t trigger_ms[]; - -extern volatile int need_sync; - -void set_time(uint8_t *buf); - -void print_time(curtime *T, uint32_t m); - -#endif // __MAIN_H__ - diff --git a/Timelapse_keyboard_only_lasers/timelapse.bin b/Timelapse_keyboard_only_lasers/timelapse.bin deleted file mode 100755 index 0a8b706..0000000 Binary files a/Timelapse_keyboard_only_lasers/timelapse.bin and /dev/null differ diff --git a/Timelapse_keyboard_only_lasers/uart.c b/Timelapse_keyboard_only_lasers/uart.c deleted file mode 100644 index ecaaab4..0000000 --- a/Timelapse_keyboard_only_lasers/uart.c +++ /dev/null @@ -1,247 +0,0 @@ -/* - * uart.c - functions to work with UART - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "uart.h" -#include "hardware_ini.h" - -// Buffers for Tx -static UART_buff TX_buffer[2]; // Tx buffers for all three ports -static UART_buff RX_buffer[2]; // Rx buffers for all three ports - -void fill_uart_RXbuff(uint32_t UART, uint8_t byte); - -/** - * Set UART speed - * @param lc - UART parameters or NULL for value from cdcacm.c (started - B115200,8,N,1) - */ -void UART_setspeed(uint32_t UART){ - usart_set_baudrate(UART, 9600); - usart_set_databits(UART, 8); - usart_set_stopbits(UART, USART_STOPBITS_1); - usart_set_parity(UART, USART_PARITY_NONE); - usart_set_flow_control(UART, USART_FLOWCONTROL_NONE); - usart_set_mode(UART, USART_MODE_TX_RX); -} - -/** - * Setup UART - */ -void UART_init(uint32_t UART){ - uint32_t irq, rcc, rccgpio, gpioport, gpiopin; - switch(UART){ - case USART2: // GPS UART - irq = NVIC_USART2_IRQ; // interrupt for given USART - rcc = RCC_USART2; // RCC timing of USART - rccgpio = RCC_GPIOA; // RCC timing of GPIO pin (for output) - TX_buffer[1].end = 0; // reset counters - TX_buffer[1].start = 0; - RX_buffer[1].end = 0; - RX_buffer[1].start = 0; - // output pin setup - gpioport = GPIO_BANK_USART2_TX; - gpiopin = GPIO_USART2_TX; - break; - case USART1: - default: - irq = NVIC_USART1_IRQ; - rcc = RCC_USART1; - rccgpio = RCC_GPIOA; - TX_buffer[0].end = 0; - TX_buffer[0].start = 0; - RX_buffer[0].end = 0; - RX_buffer[0].start = 0; - gpioport = GPIO_BANK_USART1_TX; - gpiopin = GPIO_USART1_TX; - } - // enable clocking - rcc_periph_clock_enable(RCC_AFIO); // alternate functions - rcc_periph_clock_enable(rcc); // USART - rcc_periph_clock_enable(rccgpio); // GPIO pins - // enable output pin - gpio_set_mode(gpioport, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, gpiopin); - // enable IRQ - nvic_enable_irq(irq); - UART_setspeed(UART); - // Enable UART receive interrupt - USART_CR1(UART) |= USART_CR1_RXNEIE; - // Enable UART - usart_enable(UART); -} - -/* - * UART interrupts - */ -// common -void UART_isr(uint32_t UART){ - uint8_t bufidx = 0, data; - UART_buff *curbuff; - // Check if we were called because of RXNE - if(USART_SR(UART) & USART_SR_RXNE){ - // parse incoming byte - data = usart_recv(UART); - fill_uart_RXbuff(UART, data); - } - // Check if we were called because of TXE -> send next byte in buffer - if((USART_CR1(UART) & USART_CR1_TXEIE) && (USART_SR(UART) & USART_SR_TXE)){ - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - if(bufidx != curbuff->end){ // there's data in buffer - // Put data into the transmit register - usart_send(UART, curbuff->buf[bufidx]); - if(++(curbuff->start) == UART_BUF_DATA_SIZE){ // reload start - curbuff->start = 0; - } - }else{ // Disable the TXE interrupt, it's no longer needed - USART_CR1(UART) &= ~USART_CR1_TXEIE; - // empty indexes - curbuff->start = 0; - curbuff->end = 0; - } - } -} -// particular interrupt handlers -void usart1_isr(){ - UART_isr(USART1); -} -void usart2_isr(){ - UART_isr(USART2); -} - -// put byte into Tx buffer -void fill_uart_buff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx = 0, endidx; - if(!(USART_CR1(UART) & USART_CR1_UE)) return; // UART disabled - USART_CR1(UART) &= ~USART_CR1_TXEIE; // disable TX interrupt while buffer filling - while ((USART_SR(UART) & USART_SR_TXE) == 0); // wait until last byte send - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &TX_buffer[bufidx]; - bufidx = curbuff->start; // start of data in buffer - endidx = curbuff->end; // end of data - curbuff->buf[endidx++] = byte; // put byte into buffer - // now check indexes - if(endidx != bufidx && endidx != UART_BUF_DATA_SIZE){ // all OK - there's enough place for data - (curbuff->end)++; // just increment index in buffer - }else{ // dangerous situation: possible overflow - if(endidx == UART_BUF_DATA_SIZE){ // end of buffer - if(bufidx != 0){ // no overflow - curbuff->end = 0; - goto end_of_fn; - } - } - // overflow: purge all data - bufidx = curbuff->start; // refresh data index - for(endidx = bufidx; endidx < UART_BUF_DATA_SIZE; endidx++) // first data porion - usart_send(UART, curbuff->buf[endidx]); - for(endidx = 0; endidx < bufidx; endidx++) // rest of data - usart_send(UART, curbuff->buf[endidx]); - curbuff->start = 0; - curbuff->end = 0; - return; - } - end_of_fn: - // enable interrupts to send data from buffer - USART_CR1(UART) |= USART_CR1_TXEIE; -} - -/** - * send data over UART - one function for each uart - * @param byte - one byte to put in UART queue - */ -void uart1_send(uint8_t byte){ - fill_uart_buff(USART1, byte); -} -void uart2_send(uint8_t byte){ - fill_uart_buff(USART2, byte); -} - - -/** - * Check whether UART2 have a full text line - * @return string with data if data ready or NULL - */ -uint8_t *check_UART2(){ - static int oldlen = 0; - static uint8_t buf[UART_BUF_DATA_SIZE+1]; - UART_buff *curbuff = &RX_buffer[1]; - uint8_t datalen = curbuff->end; // length of data in buffer - here we use param "end" - if(!datalen) return NULL; // buffer is empty - if(oldlen != datalen){ - if(curbuff->buf[curbuff->end-1] != '\n'){ // string not full - oldlen = datalen; - return NULL; - }else{ // full string - copy it to buffer & clear indexes - memcpy(buf, curbuff->buf, datalen); - buf[datalen] = 0; - oldlen = curbuff->end = 0; - return buf; - } - } - return NULL; -} - -/** - * Fill data in RX buffer to prepare it for further work - * we don't use "start" parameter here, it's 0 always - * @param UART - device to fill buffer - * @param byte - data byte - */ -void fill_uart_RXbuff(uint32_t UART, uint8_t byte){ - UART_buff *curbuff; - uint8_t bufidx; - switch(UART){ - case USART1: - bufidx = 0; - break; - case USART2: - bufidx = 1; - break; - default: // error - return - return; - } - curbuff = &RX_buffer[bufidx]; - if(curbuff->end == UART_BUF_DATA_SIZE){ // end of buffer - forget about data - curbuff->end = 0; - return; - } - curbuff->buf[curbuff->end++] = byte; // put byte into buffer -} diff --git a/Timelapse_keyboard_only_lasers/uart.h b/Timelapse_keyboard_only_lasers/uart.h deleted file mode 100644 index 85715ca..0000000 --- a/Timelapse_keyboard_only_lasers/uart.h +++ /dev/null @@ -1,46 +0,0 @@ -/* - * uart.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __UART_H__ -#define __UART_H__ - -// Size of buffers -#define UART_BUF_DATA_SIZE 128 - -typedef struct { - uint8_t buf[UART_BUF_DATA_SIZE]; - uint8_t start; // index from where to start reading - uint8_t end; // index from where to start writing -} UART_buff; - -void UART_init(uint32_t UART); -void UART_setspeed(uint32_t UART); - -void fill_uart_buff(uint32_t UART, uint8_t byte); -void uart1_send(uint8_t byte); -void uart2_send(uint8_t byte); - -uint8_t *check_UART2(); - -UART_buff *get_uart_buffer(uint32_t UART); - -#endif // __UART_H__ diff --git a/Timelapse_keyboard_only_lasers/usbkeybrd.c b/Timelapse_keyboard_only_lasers/usbkeybrd.c deleted file mode 100644 index b5b7a77..0000000 --- a/Timelapse_keyboard_only_lasers/usbkeybrd.c +++ /dev/null @@ -1,276 +0,0 @@ -/* - * usbkeybrd.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "usbkeybrd.h" -#include "keycodes.h" - -#define BUFLEN (1024) -static char sendbuf[BUFLEN]; -static char *msg_start = sendbuf, *msg_end = sendbuf; -static const char *buf_end = sendbuf+BUFLEN; - -usbd_device *usbd_dev; - -const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = 0, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, -// 0x045E 0x005C - Microsoft Office Keyboard (106/109) - .idVendor = 0x045E, - .idProduct = 0x005C, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -static const uint8_t hid_report_descriptor[] = { - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x06, /* Usage (Keyboard) */ - 0xA1, 0x01, /* Collection (Application) */ -// 0x85, 0x02, /* Report ID */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0xE0, /* Usage Minimum (224) */ - 0x29, 0xE7, /* Usage Maximum (231) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (1) */ - 0x75, 0x01, /* Report Size (1) */ - 0x95, 0x08, /* Report Count (8) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (8) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x95, 0x05, /* Report Count (5) */ - 0x75, 0x01, /* Report Size (1) */ - 0x05, 0x08, /* Usage Page (Page# for LEDs) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x05, /* Usage Maximum (05) */ - 0x91, 0x02, /* Output (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x03, /* Report Size (3) */ - 0x91, 0x01, /* Output (Constant) */ - 0x95, 0x06, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (3) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x65, /* Logical Maximum (101) */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0x00, /* Usage Minimum (00) */ - 0x29, 0x65, /* Usage Maximum (101) */ - 0x81, 0x00, /* Input (Data, Array) */ - 0x09, 0x05, /* Usage (Vendor Defined) */ - 0x15, 0x00, /* Logical Minimum (0)) */ - 0x26, 0xFF, 0x00, /* Logical Maximum (255)) */ - 0x75, 0x08, /* Report Count (2)) */ - 0x95, 0x02, /* Report Size (8 bit)) */ - 0xB1, 0x02, /* Feature (Data, Variable, Absolute) */ - 0xC0 /* End Collection,End Collection */ -}; - -static const struct { - struct usb_hid_descriptor hid_descriptor; - struct { - uint8_t bReportDescriptorType; - uint16_t wDescriptorLength; - } __attribute__((packed)) hid_report; -} __attribute__((packed)) hid_function = { - .hid_descriptor = { - .bLength = sizeof(hid_function), - .bDescriptorType = USB_DT_HID, - .bcdHID = 0x0100, - .bCountryCode = 0, - .bNumDescriptors = 1, - }, - .hid_report = { - .bReportDescriptorType = USB_DT_REPORT, - .wDescriptorLength = sizeof(hid_report_descriptor), - }, -}; - -const struct usb_endpoint_descriptor hid_endpoint = { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x81, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 8, - .bInterval = 0x10, -}; - -const struct usb_interface_descriptor hid_iface = { - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_HID, - .bInterfaceSubClass = 1, // boot - .bInterfaceProtocol = 1, // keyboard - .iInterface = 0, - - .endpoint = &hid_endpoint, - - .extra = &hid_function, - .extralen = sizeof(hid_function), -}; - -const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = &hid_iface, -}}; - -const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 1, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0xC0, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Timelapse keyboard", - "EEV", - "v01", -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; -static int got_config = 0; -static int hid_control_request(usbd_device *usbddev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, - void (**complete)(usbd_device *usbddev, struct usb_setup_data *req)){ - (void)complete; - (void)usbddev; - - if ((req->bmRequestType != 0x81) || - (req->bRequest != USB_REQ_GET_DESCRIPTOR) || - (req->wValue != 0x2200)) - return 0; - - *buf = (uint8_t *)hid_report_descriptor; - *len = sizeof(hid_report_descriptor); - got_config = 1; - return 1; -} - -void hid_set_config(usbd_device *usbddev, uint16_t wValue){ - (void)wValue; - (void)usbddev; - usbd_ep_setup(usbd_dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL); - usbd_register_control_callback( - usbddev, - USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - hid_control_request); -} - -void usbkeybrd_setup(){ - usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - usbd_register_set_config_callback(usbd_dev, hid_set_config); -} - -void put_char_to_buf(char ch){ - *(msg_end++) = ch; - if(msg_end == buf_end) - msg_end = sendbuf; -} - -/** - * put data into keyboard buffer - * THERE's NO DATA CORRUPTION CONTROL HERE!!! - */ -void send_msg(char *msg){ - while(*msg){ - put_char_to_buf(*(msg++)); - } -} -/* -void newline(){ - put_char_to_buf('\n'); -}*/ - -/** - * send data from keyboard buffer - */ -void process_usbkbrd(){ - if(!got_config) return; // don't allow sending messages until first connection - to prevent hangs - static uint8_t pressed = 0; - if(pressed){ // the keyboard was "pressed" - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, release_key(), 8)) - pressed = 0; - }else if(msg_start != msg_end){ // we need to send keypress event - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, press_key(*msg_start), 8)){ - if(++msg_start == buf_end) - msg_start = sendbuf; - pressed = 1; - } - }else return; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - inline void putc(char c){ - if(c < 10) - put_char_to_buf(c + '0'); - else - put_char_to_buf(c + 'a' - 10); - } - put_char_to_buf('0'); - put_char_to_buf('x'); - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - char buf[10]; - int32_t L = 0; - if(N < 0){ - put_char_to_buf('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) put_char_to_buf(buf[L]); - }else put_char_to_buf('0'); -} - diff --git a/Timelapse_keyboard_only_lasers/usbkeybrd.h b/Timelapse_keyboard_only_lasers/usbkeybrd.h deleted file mode 100644 index ab3de8f..0000000 --- a/Timelapse_keyboard_only_lasers/usbkeybrd.h +++ /dev/null @@ -1,44 +0,0 @@ -/* - * usbkeybrd.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USBKEYBRD_H__ -#define __USBKEYBRD_H__ - -#include "main.h" - -extern usbd_device *usbd_dev; - -void process_usbkbrd(); -void send_msg(char *msg); -void put_char_to_buf(char ch); -#define P(x) send_msg(x) -void usbkeybrd_setup(); - -void print_hex(uint8_t *buff, uint8_t l); -void print_int(int32_t N); - -//void newline(); -#define newline() do{put_char_to_buf('\n');}while(0) - -#define poll_usbkeybrd() usbd_poll(usbd_dev) - -#endif // __USBKEYBRD_H__ diff --git a/USBCDC_template/Makefile b/USBCDC_template/Makefile deleted file mode 100644 index 632b018..0000000 --- a/USBCDC_template/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = usb_cdc_simple -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/USBCDC_template/README b/USBCDC_template/README deleted file mode 100644 index 717ea64..0000000 --- a/USBCDC_template/README +++ /dev/null @@ -1,5 +0,0 @@ -Template of USB-CDC - -written for chinese devboard based on STM32F103R8T6 - -Press H for help \ No newline at end of file diff --git a/USBCDC_template/cdcacm.c b/USBCDC_template/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/USBCDC_template/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/USBCDC_template/cdcacm.h b/USBCDC_template/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/USBCDC_template/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/USBCDC_template/hardware_ini.c b/USBCDC_template/hardware_ini.c deleted file mode 100644 index 0e8734d..0000000 --- a/USBCDC_template/hardware_ini.c +++ /dev/null @@ -1,68 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - /* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); - */ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} diff --git a/USBCDC_template/hardware_ini.h b/USBCDC_template/hardware_ini.h deleted file mode 100644 index 5e00745..0000000 --- a/USBCDC_template/hardware_ini.h +++ /dev/null @@ -1,58 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/USBCDC_template/ld/devices.data b/USBCDC_template/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/USBCDC_template/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/USBCDC_template/ld/stm32f103x4.ld b/USBCDC_template/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/USBCDC_template/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103x6.ld b/USBCDC_template/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/USBCDC_template/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103x8.ld b/USBCDC_template/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/USBCDC_template/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xB.ld b/USBCDC_template/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/USBCDC_template/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xC.ld b/USBCDC_template/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/USBCDC_template/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xD.ld b/USBCDC_template/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/USBCDC_template/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xE.ld b/USBCDC_template/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/USBCDC_template/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xF.ld b/USBCDC_template/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/USBCDC_template/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/ld/stm32f103xG.ld b/USBCDC_template/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/USBCDC_template/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/USBCDC_template/main.c b/USBCDC_template/main.c deleted file mode 100644 index 925ac78..0000000 --- a/USBCDC_template/main.c +++ /dev/null @@ -1,86 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/USBCDC_template/main.h b/USBCDC_template/main.h deleted file mode 100644 index 36090dc..0000000 --- a/USBCDC_template/main.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/USBCDC_template/sync.c b/USBCDC_template/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/USBCDC_template/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/USBCDC_template/sync.h b/USBCDC_template/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/USBCDC_template/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/USBCDC_template/usb_cdc_simple.bin b/USBCDC_template/usb_cdc_simple.bin deleted file mode 100755 index e349c46..0000000 Binary files a/USBCDC_template/usb_cdc_simple.bin and /dev/null differ diff --git a/USBCDC_template/user_proto.c b/USBCDC_template/user_proto.c deleted file mode 100644 index dc874d9..0000000 --- a/USBCDC_template/user_proto.c +++ /dev/null @@ -1,104 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" - -void help(){ - P("H\tshow this help\n"); -} - - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - int i; - for(i = 0; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'H': // show help - help(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - usb_send(command); // echo readed byte - } - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/USBCDC_template/user_proto.h b/USBCDC_template/user_proto.h deleted file mode 100644 index 69bf771..0000000 --- a/USBCDC_template/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/canon_lens/Makefile b/canon_lens/Makefile deleted file mode 100644 index aa0a5d6..0000000 --- a/canon_lens/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = canon_lens -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/canon_lens/README b/canon_lens/README deleted file mode 100644 index ee5062d..0000000 --- a/canon_lens/README +++ /dev/null @@ -1,11 +0,0 @@ -Canon lens managing - -Functions: -- change focus -- aquire focus motor position -- change diafragm -- allow to send any commands you want ('\n' terminates list, commands can be in octal, hexadecimal or decimal format separated by any non-digital symbol) - -written for chinese devboard based on STM32F103R8T6 - -Press H for help \ No newline at end of file diff --git a/canon_lens/canon_lens.bin b/canon_lens/canon_lens.bin deleted file mode 100755 index 25bb828..0000000 Binary files a/canon_lens/canon_lens.bin and /dev/null differ diff --git a/canon_lens/cdcacm.c b/canon_lens/cdcacm.c deleted file mode 100644 index 62a7a78..0000000 --- a/canon_lens/cdcacm.c +++ /dev/null @@ -1,324 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -uint8_t usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data -uint8_t data_rdy = 0; // got full line or buffer is full - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - if(len < 1) return; - int i, ol = usbdatalen; - usbdatalen += len; - // echo readed data - for(i = ol; i < usbdatalen; ++i) usb_send(usbdatabuf[i]); - // check for end of input - if(usbdatalen == USB_RX_DATA_SIZE || usbdatabuf[usbdatalen-1] == '\n'){ - ++data_rdy; - } -} - -void empty_buf(){ - data_rdy = 0; - usbdatalen = 0; -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/canon_lens/cdcacm.h b/canon_lens/cdcacm.h deleted file mode 100644 index 76a0914..0000000 --- a/canon_lens/cdcacm.h +++ /dev/null @@ -1,58 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE (64) -#define USB_RX_DATA_SIZE (256) - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern uint8_t usbdatabuf[]; -extern int usbdatalen; - -extern uint8_t data_rdy; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -void empty_buf(); - -#endif // __CCDCACM_H__ diff --git a/canon_lens/hardware_ini.c b/canon_lens/hardware_ini.c deleted file mode 100644 index 0e8734d..0000000 --- a/canon_lens/hardware_ini.c +++ /dev/null @@ -1,68 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - /* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); - */ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} diff --git a/canon_lens/hardware_ini.h b/canon_lens/hardware_ini.h deleted file mode 100644 index 5e00745..0000000 --- a/canon_lens/hardware_ini.h +++ /dev/null @@ -1,58 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/canon_lens/ld/devices.data b/canon_lens/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/canon_lens/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/canon_lens/ld/stm32f103x4.ld b/canon_lens/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/canon_lens/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103x6.ld b/canon_lens/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/canon_lens/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103x8.ld b/canon_lens/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/canon_lens/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xB.ld b/canon_lens/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/canon_lens/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xC.ld b/canon_lens/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/canon_lens/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xD.ld b/canon_lens/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/canon_lens/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xE.ld b/canon_lens/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/canon_lens/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xF.ld b/canon_lens/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/canon_lens/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/ld/stm32f103xG.ld b/canon_lens/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/canon_lens/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/canon_lens/main.c b/canon_lens/main.c deleted file mode 100644 index b983d45..0000000 --- a/canon_lens/main.c +++ /dev/null @@ -1,88 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "spi.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - SPI_init(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - while(1){ - usbd_poll(usbd_dev); - if(data_rdy){ // there's something in USB buffer - parse_incoming_buf(); - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/canon_lens/main.h b/canon_lens/main.h deleted file mode 100644 index 36090dc..0000000 --- a/canon_lens/main.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/canon_lens/spi.c b/canon_lens/spi.c deleted file mode 100644 index 0efd45d..0000000 --- a/canon_lens/spi.c +++ /dev/null @@ -1,78 +0,0 @@ -/* - * spi.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "spi.h" - -/* - * Configure SPI ports - */ -/* - * SPI1 remapped: - * SCK - PB3 - * MISO - PB4 - * MOSI - PB5 - * - */ -void SPI_init(){ - // enable AFIO & other clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, - RCC_APB2ENR_SPI1EN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - // remap SPI1 (change pins from PA5..7 to PB3..5); also turn off JTAG - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_SPI1_REMAP); - // SCK, MOSI - push-pull output - gpio_set_mode(GPIO_BANK_SPI1_RE_SCK, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_SCK); - gpio_set_mode(GPIO_BANK_SPI1_RE_MOSI, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_MOSI); - // MISO - opendrain in - gpio_set_mode(GPIO_BANK_SPI1_RE_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI1_RE_MISO); - rcc_set_ppre2(RCC_CFGR_PPRE2_HCLK_DIV4); - spi_reset(SPI1); - /* Set up SPI in Master mode with: - * for Canon lens SPI settings are: f~78kHz, CPOL=1, CPHA=1 - * Clock baud rate: 1/256 of peripheral clock frequency (APB2, 72MHz/4 = 18MHz) - ~70kHz - * Clock polarity: CPOL=1, CPHA=1 - * Data frame format: 8-bit - * Frame format: MSB First - */ - spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_256, SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE, - SPI_CR1_CPHA_CLK_TRANSITION_2, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST); - //nvic_enable_irq(NVIC_SPI1_IRQ); // enable SPI interrupt - spi_enable(SPI1); -} - -/** - * send 1 byte blocking - * return readed byte on success - */ -uint8_t spi_write_byte(uint8_t data){ - while(!(SPI_SR(SPI1) & SPI_SR_TXE)); - SPI_DR(SPI1) = data; - while(!(SPI_SR(SPI1) & SPI_SR_TXE)); - while(!(SPI_SR(SPI1) & SPI_SR_RXNE)); - uint8_t rd = SPI_DR(SPI1); - while(!(SPI_SR(SPI1) & SPI_SR_TXE)); - while(SPI_SR(SPI1) & SPI_SR_BSY); - return rd; -} - - diff --git a/canon_lens/spi.h b/canon_lens/spi.h deleted file mode 100644 index e0d4be6..0000000 --- a/canon_lens/spi.h +++ /dev/null @@ -1,31 +0,0 @@ -/* - * spi.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SPI_H__ -#define __SPI_H__ - -void SPI_init(); -uint8_t spiWrite(uint8_t *data, uint16_t len); -extern uint32_t Current_SPI; -uint8_t spi_write_byte(uint8_t data); - -#endif // __SPI_H__ diff --git a/canon_lens/sync.c b/canon_lens/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/canon_lens/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/canon_lens/sync.h b/canon_lens/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/canon_lens/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/canon_lens/user_proto.c b/canon_lens/user_proto.c deleted file mode 100644 index f7a5741..0000000 --- a/canon_lens/user_proto.c +++ /dev/null @@ -1,250 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "spi.h" - -void help(){ - P("c\tmax close diaphragm\n"); - P("D\tdiaphragm 10+\n"); - P("d\tdiaphragm 10-\n"); - P("F\tmove F to 127 steps+\n"); - P("f\tmove F to 127 steps-\n"); - P("h\tshow this help\n"); - P("o\tmax open diaphragm\n"); - P("r\t(or empty line) repeat last command sequence\n"); - P("v\tshow focus value (in steps)\n"); - P("+\tgo to infinity\n"); - P("-\tgo to minimal F\n"); -} - -#define UBUFF_LEN (64) -uint8_t ubuff[UBUFF_LEN]; -int ubuff_sz = 0; - -// read unsigned char in oct,dec or hex format; if success, return 0; otherwice return 1 -// modify `buf` to point at last non-digit symbol -int read_uchar(uint8_t **buf, uint8_t *eol){ - uint8_t *start = *buf; - uint32_t readed = 0; - if(*start == '0'){ // hex or oct - if(start[1] == 'x'){ // hex - start += 2; - while(start < eol){ - char ch = *start, m = 0; - if(ch >= '0' && ch <= '9') m = '0'; - else if(ch >= 'a' && ch <= 'f') m = 'a' - 10; - else if(ch >= 'A' && ch <= 'F') m = 'A' - 10; - else break; - if(m){ - readed <<= 4; - readed |= ch - m; - } - ++start; - } - }else{ // oct - ++start; - while(start < eol){ - char ch = *start; - if(ch >= '0' && ch < '8'){ - readed <<= 3; - readed |= ch - '0'; - }else break; - ++start; - } - } - }else{ // dec - while(start < eol){ - char ch = *start; - if(ch >= '0' && ch <= '9'){ - readed *= 10; - readed += ch - '0'; - }else break; - ++start; - } - } - if(readed > 255){ - P("bad value!"); - return 1; - } - ubuff[ubuff_sz++] = (uint8_t) readed; - *buf = start; - return 0; -} - -static const uint8_t gotoplus[] = {0, 10, 7, 5, 0}; -static const uint8_t gotominus[] = {0, 10, 7, 6, 0}; -static const uint8_t diaopen[] = {0, 10, 19, 128, 0}; -static const uint8_t diaclose[] = {0, 10, 19, 127, 0}; -static const uint8_t diap[] = {0, 10, 19, ~10, 8, 0}; -static const uint8_t diam[] = {0, 10, 19, 10, 8, 0}; -static const uint8_t fmovp[] = {0, 10, 7, 68, 0, 127, 0}; -static const uint8_t fmovm[] = {0, 10, 7, 68, 255, 128, 0}; - - -void write_buff(uint8_t *buf, int len){ - int i; - for(i = 0; i < len; ++i){ - uint8_t rd = spi_write_byte(buf[i]); - print_int(i); P(": written "); print_int(buf[i]); - P(" readed "); print_int(rd); newline(); - Delay(2); - } -} - -void showFval(){ - int16_t val; - uint8_t rd = 0, *b = (uint8_t*)&val; - int i; - for(i = 0; i < 3 && rd != 0xaa; ++i){ - spi_write_byte(10); - Delay(2); - rd = spi_write_byte(0); - Delay(5); - } - if(rd != 0xaa){ - P("Something wrong: lens don't answer!\n"); - return; - } - spi_write_byte(192); - Delay(2); - b[1] = spi_write_byte(0); - Delay(2); - b[0] = spi_write_byte(0); - P("focus motor position: "); - print_int(val); - newline(); -} - -/** - * parse command buffer buf with length len - * fill uint8_t data buffer with readed data - */ -void parse_incoming_buf(){ - uint8_t *curch = usbdatabuf, *eol = usbdatabuf + usbdatalen; - uint8_t ch = *curch, data = 0; - if(usbdatalen == 2){ - switch(ch){ - case 'h': // help - help(); - break; - case 'r': // repeat last command - write_buff(ubuff, ubuff_sz); - break; -#define WRBUF(x) do{write_buff((uint8_t*)x, sizeof(x));}while(0) - case '+': // goto infty - WRBUF(gotoplus); - break; - case '-': // goto 2.5m - WRBUF(gotominus); - break; - case 'o': // open d - WRBUF(diaopen); - break; - case 'c': // close d - WRBUF(diaclose); - break; - case 'F': // f127+ - WRBUF(fmovp); - break; - case 'f': // f127- - WRBUF(fmovm); - break; - case 'd': - WRBUF(diam); - break; - case 'D': - WRBUF(diap); - break; - case 'v': - showFval(); - break; - } - empty_buf(); - return; - } - while(curch < eol){ - ch = *curch; - if(ch >= '0' && ch <= '9'){ - if(!data){data = 1; ubuff_sz = 0;} - if(read_uchar(&curch, eol)){ - ubuff_sz = 0; - break; - } - continue; - } - ++curch; - } - write_buff(ubuff, ubuff_sz); - if(eol[-1] != '\n') P("Warning! Buffer overflow, some data may be corrupt!!!"); - empty_buf(); -} - -/** - * Send char array wrd thru USB - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/canon_lens/user_proto.h b/canon_lens/user_proto.h deleted file mode 100644 index 1cf3c76..0000000 --- a/canon_lens/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -void parse_incoming_buf(); - -#endif // __USER_PROTO_H__ diff --git a/client-term/Makefile b/client-term/Makefile deleted file mode 100644 index 19bac1f..0000000 --- a/client-term/Makefile +++ /dev/null @@ -1,22 +0,0 @@ -PROGRAM = client -LDFLAGS = -SRCS = client.c -CC = gcc -DEFINES = -D_XOPEN_SOURCE=501 -CXX = gcc -CFLAGS = -Wall -Werror $(DEFINES) -OBJS = $(SRCS:.c=.o) -all : $(PROGRAM) clean -$(PROGRAM) : $(OBJS) - $(CC) $(CFLAGS) $(OBJS) $(LDFLAGS) -o $(PROGRAM) - -# some addition dependencies -# %.o: %.c -# $(CC) $(LDFLAGS) $(CFLAGS) $< -o $@ -#$(SRCS) : %.c : %.h $(INDEPENDENT_HEADERS) -# @touch $@ - -clean: - /bin/rm -f *.o *~ -depend: - $(CXX) -MM $(CXX.SRCS) diff --git a/client-term/client.c b/client-term/client.c deleted file mode 100644 index 5f565e0..0000000 --- a/client-term/client.c +++ /dev/null @@ -1,273 +0,0 @@ -/* - * client.c - simple terminal client - * - * Copyright 2013 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#include // tcsetattr -#include // tcsetattr, close, read, write -#include // ioctl -#include // printf, getchar, fopen, perror -#include // exit -#include // read -#include // read -#include // signal -#include // time -#include // memcpy -#include // int types -#include // gettimeofday - -#define BUFLEN 1024 - -double t0; // start time - -FILE *fout = NULL; // file for messages duplicating -char *comdev = "/dev/ttyACM0"; -int BAUD_RATE = B115200; -struct termio oldtty, tty; // TTY flags -struct termios oldt, newt; // terminal flags -int comfd; // TTY fd - -#define DBG(...) do{fprintf(stderr, __VA_ARGS__);}while(0) - -/** - * function for different purposes that need to know time intervals - * @return double value: time in seconds - */ -double dtime(){ - double t; - struct timeval tv; - gettimeofday(&tv, NULL); - t = tv.tv_sec + ((double)tv.tv_usec)/1e6; - return t; -} - -/** - * Exit & return terminal to old state - * @param ex_stat - status (return code) - */ -void quit(int ex_stat){ - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); // return terminal to previous state - ioctl(comfd, TCSANOW, &oldtty ); // return TTY to previous state - close(comfd); - if(fout) fclose(fout); - printf("Exit! (%d)\n", ex_stat); - exit(ex_stat); -} - -/** - * Open & setup TTY, terminal - */ -void tty_init(){ - // terminal without echo - tcgetattr(STDIN_FILENO, &oldt); - newt = oldt; - newt.c_lflag &= ~(ICANON | ECHO); - if(tcsetattr(STDIN_FILENO, TCSANOW, &newt) < 0) quit(-2); - printf("\nOpen port...\n"); - if ((comfd = open(comdev,O_RDWR|O_NOCTTY|O_NONBLOCK)) < 0){ - fprintf(stderr,"Can't use port %s\n",comdev); - quit(1); - } - printf(" OK\nGet current settings...\n"); - if(ioctl(comfd,TCGETA,&oldtty) < 0) exit(-1); // Get settings - tty = oldtty; - tty.c_lflag = 0; // ~(ICANON | ECHO | ECHOE | ISIG) - tty.c_oflag = 0; - tty.c_cflag = BAUD_RATE|CS8|CREAD|CLOCAL; // 9.6k, 8N1, RW, ignore line ctrl - tty.c_cc[VMIN] = 0; // non-canonical mode - tty.c_cc[VTIME] = 5; - if(ioctl(comfd,TCSETA,&tty) < 0) exit(-1); // set new mode - printf(" OK\n"); - tcsetattr(STDIN_FILENO, TCSANOW, &newt); -} - -/** - * getchar() without echo - * wait until at least one character pressed - * @return character readed - * -int mygetchar(){ - int ret; - do ret = read_console(); - while(ret == 0); - return ret; -}*/ - -/** - * read both tty & console - * @param buff (o) - buffer for messages readed from tty - * @param length (io) - buff's length (return readed len or 0) - * @param rb (o) - byte readed from console or -1 - * @return 1 if something was readed here or there - */ -int read_tty_and_console(char *buff, size_t *length, int *rb){ - ssize_t L; - // ssize_t l; - size_t buffsz = *length; - struct timeval tv; - int sel, retval = 0; - fd_set rfds; - FD_ZERO(&rfds); - FD_SET(STDIN_FILENO, &rfds); - FD_SET(comfd, &rfds); - tv.tv_sec = 0; tv.tv_usec = 10000; - sel = select(comfd + 1, &rfds, NULL, NULL, &tv); - if(sel > 0){ - if(FD_ISSET(STDIN_FILENO, &rfds)){ - *rb = getchar(); - retval = 1; - }else{ - *rb = -1; - } - if(FD_ISSET(comfd, &rfds)){ - if((L = read(comfd, buff, buffsz)) < 1){ // disconnect or other troubles - fprintf(stderr, "USB error or disconnected!\n"); - quit(1); - }else{ - if(L == 0){ // USB disconnected - fprintf(stderr, "USB disconnected!\n"); - quit(1); - } - // all OK continue reading - /* DBG("readed %zd bytes, try more.. ", L); - buffsz -= L; - while(buffsz > 0 && (l = read(comfd, buff+L, buffsz)) > 0){ - L += l; - buffsz -= l; - } - DBG("full len: %zd\n", L); */ - *length = (size_t) L; - retval = 1; - } - }else{ - *length = 0; - } - } - return retval; -} - -void help(){ - printf("Use this commands:\n" - "h\tShow this help\n" - "q\tQuit\n" - ); -} - -void con_sig(int rb){ - char cmd; - if(rb < 1) return; - if(rb == 'q') quit(0); // q == exit - cmd = (char) rb; - write(comfd, &cmd, 1); - /*switch(rb){ - case 'h': - help(); - break; - default: - cmd = (uint8_t) rb; - write(comfd, &cmd, 1); - }*/ -} - -/** - * Get integer value from buffer - * @param buff (i) - buffer with int - * @param len - length of data in buffer (could be 2 or 4) - * @return - */ -uint32_t get_int(char *buff, size_t len){ - if(len != 2 && len != 4){ - fprintf(stdout, "Bad data length!\n"); - return 0xffffffff; - } - uint32_t data = 0; - uint8_t *i8 = (uint8_t*) &data; - if(len == 2) memcpy(i8, buff, 2); - else memcpy(i8, buff, 4); - return data; -} - -/** - * Copy line by line buffer buff to file removing cmd starting from newline - * @param buffer - data to put into file - * @param cmd - symbol to remove from line startint (if found, change *cmd to (-1) - * or NULL, (-1) if no command to remove - */ -void copy_buf_to_file(char *buffer, int *cmd){ - char *buff, *line, *ptr; - if(!cmd || *cmd < 0){ - fprintf(fout, "%s", buffer); - return; - } - buff = strdup(buffer), ptr = buff; - do{ - if(!*ptr) break; - if(ptr[0] == (char)*cmd){ - *cmd = -1; - ptr++; - if(ptr[0] == '\n') ptr++; - if(!*ptr) break; - } - line = ptr; - ptr = strchr(buff, '\n'); - if(ptr){ - *ptr++ = 0; - //fprintf(fout, "%s\n", line); - }//else - //fprintf(fout, "%s", line); // no newline found in buffer - fprintf(fout, "%s\n", line); - }while(ptr); - free(buff); -} - -int main(int argc, char *argv[]){ - int rb, oldcmd = -1; - char buff[BUFLEN+1]; - size_t L; - if(argc == 2){ - fout = fopen(argv[1], "a"); - if(!fout){ - perror("Can't open output file"); - exit(-1); - } - setbuf(fout, NULL); - } - tty_init(); - signal(SIGTERM, quit); // kill (-15) - signal(SIGINT, quit); // ctrl+C - signal(SIGQUIT, SIG_IGN); // ctrl+\ . - signal(SIGTSTP, SIG_IGN); // ctrl+Z - setbuf(stdout, NULL); - t0 = dtime(); - while(1){ - L = BUFLEN; - if(read_tty_and_console(buff, &L, &rb)){ - if(rb > 0){ - con_sig(rb); - oldcmd = rb; - } - if(L){ - buff[L] = 0; - printf("%s", buff); - if(fout){ - copy_buf_to_file(buff, &oldcmd); - } - } - } - } -} diff --git a/distance_meters/Makefile b/distance_meters/Makefile deleted file mode 100644 index 35b162d..0000000 --- a/distance_meters/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = ultrasonic -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/distance_meters/Readme.md b/distance_meters/Readme.md deleted file mode 100644 index f9666de..0000000 --- a/distance_meters/Readme.md +++ /dev/null @@ -1,6 +0,0 @@ -### Distance meter based on ultrasonic sensor HC-SR04 & Sharp 2Y0A02 IR sensor - -The same on STM8: [livejournal](http://eddy-em.livejournal.com/66122.html) (on russian), [github](https://sourceforge.net/p/stm8samples/code/ci/default/tree/distance_meter/). - -Allow not only to measure distance by ultrasonic distance-meter but also check transits -(Sharp sensor works at analog watchdog) \ No newline at end of file diff --git a/distance_meters/cdcacm.c b/distance_meters/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/distance_meters/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/distance_meters/cdcacm.h b/distance_meters/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/distance_meters/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/distance_meters/hardware_ini.c b/distance_meters/hardware_ini.c deleted file mode 100644 index 717ab14..0000000 --- a/distance_meters/hardware_ini.c +++ /dev/null @@ -1,57 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - diff --git a/distance_meters/hardware_ini.h b/distance_meters/hardware_ini.h deleted file mode 100644 index 11fe628..0000000 --- a/distance_meters/hardware_ini.h +++ /dev/null @@ -1,60 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -#include "ultrasonic.h" - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/distance_meters/ld/devices.data b/distance_meters/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/distance_meters/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/distance_meters/ld/stm32f103x4.ld b/distance_meters/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/distance_meters/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103x6.ld b/distance_meters/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/distance_meters/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103x8.ld b/distance_meters/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/distance_meters/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xB.ld b/distance_meters/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/distance_meters/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xC.ld b/distance_meters/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/distance_meters/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xD.ld b/distance_meters/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/distance_meters/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xE.ld b/distance_meters/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/distance_meters/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xF.ld b/distance_meters/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/distance_meters/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/ld/stm32f103xG.ld b/distance_meters/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/distance_meters/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/distance_meters/main.c b/distance_meters/main.c deleted file mode 100644 index f4c1d7a..0000000 --- a/distance_meters/main.c +++ /dev/null @@ -1,120 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "sharp.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - tim2_init(); - //init_sharp_sensor(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - uint32_t oldL = 0; - while(1){ - uint32_t L; - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - if(AWD_flag){ - P("Int, value = "); - print_int(AWD_value); - P(" ADU\n"); - AWD_flag = 0; - } - if(ultrasonic_get(&L)){ - if(!cont){ - P("Measured length: "); - print_int(L); - P("mm\n"); - oldL = 0; - }else{ - if(!oldL){ - oldL = L; - }else{ - uint32_t diff = (oldL > L) ? oldL - L : L - oldL; - if(diff > MAX_LEN_DIFF){ - P("Pass! Was: "); - print_int(oldL); - P(", become: "); - print_int(L); - P("!!!\n"); - oldL = L; - } - } - start_ultrasonic(); - } - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/distance_meters/main.h b/distance_meters/main.h deleted file mode 100644 index 5dcdafb..0000000 --- a/distance_meters/main.h +++ /dev/null @@ -1,57 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -// max diff in continuous measurements - 100mm -#define MAX_LEN_DIFF (100) - -#endif // __MAIN_H__ - diff --git a/distance_meters/sharp.c b/distance_meters/sharp.c deleted file mode 100644 index f081aa8..0000000 --- a/distance_meters/sharp.c +++ /dev/null @@ -1,72 +0,0 @@ -/* - * sharp.c - functions for Sharp 2Y0A02 distance meter - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "sharp.h" -#include "main.h" - -int AWD_flag = 0; -uint16_t AWD_value = 0; - -void init_sharp_sensor(){ - // Make sure the ADC doesn't run during config - adc_off(ADC1); - // enable ADC & PA0 clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN | RCC_APB2ENR_IOPAEN); - rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4); - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0); - // set sample time: 239.5 cycles for better results - ADC1_SMPR2 = 7; - // continuous conv, enable - ADC1_CR2 = ADC_CR2_CONT | ADC_CR2_ADON; - // reset calibration registers & start calibration - ADC1_CR2 |= ADC_CR2_RSTCAL; - while(ADC1_CR2 & ADC_CR2_RSTCAL); // wait for registers reset - ADC1_CR2 |= ADC_CR2_CAL; - while(ADC1_CR2 & ADC_CR2_CAL); // wait for calibration ends - // set threshold limits - ADC1_HTR = ADC_WDG_HIGH; - ADC1_LTR = ADC_WDG_LOW; - // enable analog watchdog on single regular channel 0 & enable interrupt - ADC1_CR1 = ADC_CR1_AWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDIE; - nvic_enable_irq(NVIC_ADC1_2_IRQ); - ADC1_CR2 |= ADC_CR2_SWSTART; - // start - to do it we need set ADC_CR2_ADON again! - ADC1_CR2 |= ADC_CR2_ADON; - DBG("ADC started\n"); -} - -void adc1_2_isr(){ - AWD_value = ADC1_DR; - if(ADC1_SR & ADC_SR_AWD){ // analog watchdog event - AWD_flag = 1; - // ADC1_CR1 &= ~(ADC_CR1_AWDIE | ADC_CR1_AWDEN); - // nvic_disable_irq(NVIC_ADC1_2_IRQ); - if(AWD_value >= ADC_WDG_HIGH){ // high threshold - ADC1_HTR = 0x0fff; // remove high threshold, only wait for LOW - ADC1_LTR = ADC_WDG_LOW; - }else{ - ADC1_HTR = ADC_WDG_HIGH; - ADC1_LTR = 0; - } - //ADC1_CR1 |= ADC_CR1_AWDIE; - } - ADC1_SR = 0; -} diff --git a/distance_meters/sharp.h b/distance_meters/sharp.h deleted file mode 100644 index c2d48bb..0000000 --- a/distance_meters/sharp.h +++ /dev/null @@ -1,38 +0,0 @@ -/* - * sharp.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SHARP_H__ -#define __SHARP_H__ - -#include - -extern int AWD_flag; -extern uint16_t AWD_value; - -// > 2.5V - something nearest 1m -#define ADC_WDG_HIGH ((uint16_t)3000) -// < 0.6V - nothing in front of sensor -#define ADC_WDG_LOW ((uint16_t)750) - -void init_sharp_sensor(); - -#endif // __SHARP_H__ diff --git a/distance_meters/sync.c b/distance_meters/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/distance_meters/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/distance_meters/sync.h b/distance_meters/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/distance_meters/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/distance_meters/ultrasonic.bin b/distance_meters/ultrasonic.bin deleted file mode 100755 index 305d3b2..0000000 Binary files a/distance_meters/ultrasonic.bin and /dev/null differ diff --git a/distance_meters/ultrasonic.c b/distance_meters/ultrasonic.c deleted file mode 100644 index 41d010c..0000000 --- a/distance_meters/ultrasonic.c +++ /dev/null @@ -1,165 +0,0 @@ -/* - * ultrasonic.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include -#include -#include -#include - -#include "ultrasonic.h" -#include "user_proto.h" - -static usmode US_mode = US_MODE_OFF; -static int overcapture = 0; - -#ifndef TIM_CCMR2_CC3S_IN_TI4 -#define TIM_CCMR2_CC3S_IN_TI4 (2) -#endif -#ifndef TIM_CCMR2_CC4S_IN_TI4 -#define TIM_CCMR2_CC4S_IN_TI4 (1 << 8) -#endif -/** - * Init timer 2 (&remap channels 3&4 to five-tolerant ports) - */ -void tim2_init(){ - // Turn off JTAG & SWD, remap TIM2_CH3/TIM2_CH4 to PB10/PB11 (five tolerant) - // don't forget about AFIO clock & PB clock! - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP2); - // setup PB10 & PB11 - // PB10 - Trig output - push/pull - gpio_set_mode(GPIO_BANK_TIM2_PR2_CH3, GPIO_MODE_OUTPUT_10_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_PR2_CH3); -// gpio_set_mode(GPIO_BANK_TIM2_CH3, GPIO_MODE_OUTPUT_10_MHZ, -// GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_CH3); - // PB11 - Echo input - floating -// gpio_set_mode(GPIO_BANK_TIM2_PR2_CH4, GPIO_MODE_INPUT, -// GPIO_CNF_INPUT_FLOAT, GPIO_TIM2_PR2_CH4); - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - // 36MHz of APB1 - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM2_PSC = 71; // prescaler is (div - 1) - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; -// DBG("Timer configured\n"); -} - -/** - * Send Trig signal - * return 0 if another measurement still in process - */ -int start_ultrasonic(){ - if(US_mode != US_MODE_OFF && US_mode != US_MODE_READY) return 0; - overcapture = 0; - TIM2_CR1 = 0; - //TIM2_CR1 = TIM_CR1_URS; // Turn off timer to reconfigure, dusable UEV by UG set - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_DIER = 0; - TIM2_SR = 0; // clear all flags - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; - // PWM_OUT for TIM2_CH3 - TIM2_CCMR2 = TIM_CCMR2_CC3S_OUT | TIM_CCMR2_OC3M_PWM1; - // start measurement, active is high - TIM2_CCER = TIM_CCER_CC3E; - // enable CC3 IRQ - TIM2_DIER = TIM_DIER_CC3IE; - nvic_enable_irq(NVIC_TIM2_IRQ); - US_mode = US_MODE_TRIG; - // start timer in one-pulse mode without update event - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN | TIM_CR1_UDIS; - return 1; -} - -/** - * Start measurement: - * TIM2_CH3 will capture high level & TIM2_CH4 will capture low - * The timer configured to 65536us to detect signal lost - */ -inline void run_measrmnt(){ - US_mode = US_MODE_WAIT; - TIM2_CR1 = 0; // Turn off timer to reconfigure - TIM2_DIER = 0; - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - //DBG("triggered\n"); - TIM2_SR = 0; // clear all flags - TIM2_ARR = MAX_MSRMNT_LEN; - // TIM2_CH3 & TIM2_CH4 configured as inputs, TIM2_CH3 connected to CH4 - TIM2_CCMR2 = TIM_CCMR2_CC3S_IN_TI4 | TIM_CCMR2_CC4S_IN_TI4; - // start - TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; - // enable interrupts CH3, CH4 & update - TIM2_DIER = TIM_DIER_CC3IE | TIM_DIER_CC4IE | TIM_DIER_UIE; - // start timer in one-pulse mode - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN; -} - -void tim2_isr(){ - // No signal - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - TIM2_SR = 0; - overcapture = 1; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - US_mode = US_MODE_READY; - DBG("overcaptured\n"); - } - // end of Trig pulse or start of measurements - if(TIM2_SR & TIM_SR_CC3IF){ // CCR ch3 interrupt - if(US_mode == US_MODE_TRIG){ // triggered - run measurement - run_measrmnt(); - }else if(US_mode == US_MODE_WAIT){ - US_mode = US_MODE_MEASUREMENT; - } - TIM2_SR &= ~TIM_SR_CC3IF; - } - if(TIM2_SR & TIM_SR_CC4IF){ - if(US_mode == US_MODE_MEASUREMENT){ - US_mode = US_MODE_READY; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - TIM2_CR1 = 0; // turn off timer - we don't need it more - } - TIM2_SR &= ~TIM_SR_CC3IF; - } -} - -/** - * Measure distance - * return 1 if measurements done - * set L to distance (in mm) or 0 in case of overcapture (no signal) - */ -int ultrasonic_get(uint32_t *L){ - uint32_t D; - if(US_mode != US_MODE_READY) - return 0; - US_mode = US_MODE_OFF; - if(!overcapture){ - D = ((uint32_t)(TIM2_CCR4 - TIM2_CCR3)) * 170; - *L = D / 1000; - }else *L = 0; - return 1; -} diff --git a/distance_meters/ultrasonic.h b/distance_meters/ultrasonic.h deleted file mode 100644 index 86432dc..0000000 --- a/distance_meters/ultrasonic.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * ultrasonic.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __ULTRASONIC_H__ -#define __ULTRASONIC_H__ - -#include - -void tim2_init(); -int start_ultrasonic(); -int ultrasonic_get(uint32_t *L); - - -// Sensor mode -typedef enum{ - US_MODE_OFF // sensor is off - ,US_MODE_TRIG // sensor triggered - ,US_MODE_WAIT // wait for pulse - ,US_MODE_MEASUREMENT // measurement in process - ,US_MODE_READY // measurements done -} usmode; - -// trigger time: after trigger event ends, timer will be configured for capture - 20us -#define TRIG_T (200) -// trigger length - 10us -#define TRIG_L (10) -// max length of measurement (to detect signal absence) -#define MAX_MSRMNT_LEN (65535) - -#endif // __ULTRASONIC_H__ diff --git a/distance_meters/user_proto.c b/distance_meters/user_proto.c deleted file mode 100644 index 8e7f3f0..0000000 --- a/distance_meters/user_proto.c +++ /dev/null @@ -1,213 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "sharp.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD, cont = 0; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("A\tshow ADC value\n"); - P("H\tshow this help\n"); - P("D\tmeasure distance\n"); - P("I\tinit sharp\n"); - P("T\tshow timer value\n"); - P("S\tstart/stop continuous measurement\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'A': - P("ADC: "); - print_int(ADC1_DR); - P("ADU\n"); - break; - case 'D': - if(!start_ultrasonic()) - P("Can't start: another measurement is in process!\n"); - break; - case 'H': // show help - help(); - break; - case 'I': - init_sharp_sensor(); - break; - case 'S': - cont = !cont; - if(cont) start_ultrasonic(); - break; - case 'T': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/distance_meters/user_proto.h b/distance_meters/user_proto.h deleted file mode 100644 index d9af859..0000000 --- a/distance_meters/user_proto.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -extern uint8_t cont; - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/hid_mouse_keyboard/Makefile b/hid_mouse_keyboard/Makefile deleted file mode 100644 index 94ccdc0..0000000 --- a/hid_mouse_keyboard/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = usbhid -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103xB.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/hid_mouse_keyboard/Readme.md b/hid_mouse_keyboard/Readme.md deleted file mode 100644 index 91a7553..0000000 --- a/hid_mouse_keyboard/Readme.md +++ /dev/null @@ -1,5 +0,0 @@ -### USB HID mouse & keyboard - -This is a very simple example of simultaneous STM32 work as compound USB-HID device: usb & mouse. -Written for STM32F103RBT6 -When you connect your device to computer it will move mouse cursor by square 40x40 and write text "top/bottom right/left" on each corner. diff --git a/hid_mouse_keyboard/keycodes.c b/hid_mouse_keyboard/keycodes.c deleted file mode 100644 index 39b09b0..0000000 --- a/hid_mouse_keyboard/keycodes.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * keycodes.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "keycodes.h" -/* - * Keyboard buffer: - * buf[1]: MOD - * buf[2]: reserved - * buf[3]..buf[8] - keycodes 1..6 - */ -static uint8_t buf[9] = {2,0,0,0,0,0,0,0,0}; - -#define _(x) (x|0x80) -// array for keycodes according to ASCII table; MSB is MOD_SHIFT flag -static const uint8_t keycodes[] = { - // space !"#$%&' - KEY_SPACE, _(KEY_1), _(KEY_QUOTE), _(KEY_3), _(KEY_4), _(KEY_5), _(KEY_7), KEY_QUOTE, - // ()*+,-./ - _(KEY_9), _(KEY_0), _(KEY_8), _(KEY_EQUAL), KEY_COMMA, KEY_MINUS, KEY_PERIOD, KEY_SLASH, - // 0..9 - 39, 30, 31, 32, 33, 34, 35, 36, 37, 38, - // :;<=>?@ - _(KEY_SEMICOLON), KEY_SEMICOLON, _(KEY_COMMA), KEY_EQUAL, _(KEY_PERIOD), _(KEY_SLASH), _(KEY_2), - // A..Z: for a in $(seq 0 25); do printf "$((a+132)),"; done - 132,133,134,135,136,137,138,139,140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157, - // [\]^_` - KEY_LEFT_BRACE, KEY_BACKSLASH, KEY_RIGHT_BRACE, _(KEY_6), _(KEY_MINUS), KEY_TILDE, - // a..z: for a in $(seq 0 25); do printf "$((a+4)),"; done - 4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29, - // {|}~ - _(KEY_LEFT_BRACE), _(KEY_BACKSLASH), _(KEY_RIGHT_BRACE), _(KEY_TILDE) -}; - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY){ - buf[1] = MOD; - buf[3] = KEY; - return buf; -} - -/** - * return buffer for sending symbol "ltr" with addition modificator mod - */ -uint8_t *press_key_mod(char ltr, uint8_t mod){ - uint8_t MOD = 0; - uint8_t KEY = 0; - if(ltr > 31){ - KEY = keycodes[ltr - 32]; - if(KEY & 0x80){ - MOD = MOD_SHIFT; - KEY &= 0x7f; - } - }else if (ltr == '\n') KEY = KEY_ENTER; - buf[1] = MOD | mod; - buf[3] = KEY; - return buf; -} diff --git a/hid_mouse_keyboard/keycodes.h b/hid_mouse_keyboard/keycodes.h deleted file mode 100644 index 98a2fa1..0000000 --- a/hid_mouse_keyboard/keycodes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* - * keycodes.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __KEYKODES_H__ -#define __KEYKODES_H__ - -#include - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY); -#define release_key() set_key_buf(0,0) -uint8_t *press_key_mod(char key, uint8_t mod); -#define press_key(k) press_key_mod(k, 0) - -#define MOD_CTRL 0x01 -#define MOD_SHIFT 0x02 -#define MOD_ALT 0x04 -#define MOD_GUI 0x08 - -#define LEFT(mod) (mod) -#define RIGHT(mod) ((mod << 4)) - -#define KEY_A 4 -#define KEY_B 5 -#define KEY_C 6 -#define KEY_D 7 -#define KEY_E 8 -#define KEY_F 9 -#define KEY_G 10 -#define KEY_H 11 -#define KEY_I 12 -#define KEY_J 13 -#define KEY_K 14 -#define KEY_L 15 -#define KEY_M 16 -#define KEY_N 17 -#define KEY_O 18 -#define KEY_P 19 -#define KEY_Q 20 -#define KEY_R 21 -#define KEY_S 22 -#define KEY_T 23 -#define KEY_U 24 -#define KEY_V 25 -#define KEY_W 26 -#define KEY_X 27 -#define KEY_Y 28 -#define KEY_Z 29 -#define KEY_1 30 -#define KEY_2 31 -#define KEY_3 32 -#define KEY_4 33 -#define KEY_5 34 -#define KEY_6 35 -#define KEY_7 36 -#define KEY_8 37 -#define KEY_9 38 -#define KEY_0 39 -#define KEY_ENTER 40 -#define KEY_ESC 41 -#define KEY_BACKSPACE 42 -#define KEY_TAB 43 -#define KEY_SPACE 44 -#define KEY_MINUS 45 -#define KEY_EQUAL 46 -#define KEY_LEFT_BRACE 47 -#define KEY_RIGHT_BRACE 48 -#define KEY_BACKSLASH 49 -#define KEY_NUMBER 50 -#define KEY_SEMICOLON 51 -#define KEY_QUOTE 52 -#define KEY_TILDE 53 -#define KEY_COMMA 54 -#define KEY_PERIOD 55 -#define KEY_SLASH 56 -#define KEY_CAPS_LOCK 57 -#define KEY_F1 58 -#define KEY_F2 59 -#define KEY_F3 60 -#define KEY_F4 61 -#define KEY_F5 62 -#define KEY_F6 63 -#define KEY_F7 64 -#define KEY_F8 65 -#define KEY_F9 66 -#define KEY_F10 67 -#define KEY_F11 68 -#define KEY_F12 69 -#define KEY_PRINTSCREEN 70 -#define KEY_SCROLL_LOCK 71 -#define KEY_PAUSE 72 -#define KEY_INSERT 73 -#define KEY_HOME 74 -#define KEY_PAGE_UP 75 -#define KEY_DELETE 76 -#define KEY_END 77 -#define KEY_PAGE_DOWN 78 -#define KEY_RIGHT 79 -#define KEY_LEFT 80 -#define KEY_DOWN 81 -#define KEY_UP 82 -#define KEY_NUM_LOCK 83 -#define KEYPAD_SLASH 84 -#define KEYPAD_ASTERIX 85 -#define KEYPAD_MINUS 86 -#define KEYPAD_PLUS 87 -#define KEYPAD_ENTER 88 -#define KEYPAD_1 89 -#define KEYPAD_2 90 -#define KEYPAD_3 91 -#define KEYPAD_4 92 -#define KEYPAD_5 93 -#define KEYPAD_6 94 -#define KEYPAD_7 95 -#define KEYPAD_8 96 -#define KEYPAD_9 97 -#define KEYPAD_0 98 -#define KEYPAD_PERIOD 99 - -#endif // __KEYKODES_H__ diff --git a/hid_mouse_keyboard/ld/devices.data b/hid_mouse_keyboard/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/hid_mouse_keyboard/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/hid_mouse_keyboard/ld/stm32f103x4.ld b/hid_mouse_keyboard/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/hid_mouse_keyboard/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103x6.ld b/hid_mouse_keyboard/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/hid_mouse_keyboard/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103x8.ld b/hid_mouse_keyboard/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/hid_mouse_keyboard/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xB.ld b/hid_mouse_keyboard/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xC.ld b/hid_mouse_keyboard/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xD.ld b/hid_mouse_keyboard/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xE.ld b/hid_mouse_keyboard/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xF.ld b/hid_mouse_keyboard/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/ld/stm32f103xG.ld b/hid_mouse_keyboard/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/hid_mouse_keyboard/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/hid_mouse_keyboard/usbhid.bin b/hid_mouse_keyboard/usbhid.bin deleted file mode 100755 index 300e091..0000000 Binary files a/hid_mouse_keyboard/usbhid.bin and /dev/null differ diff --git a/hid_mouse_keyboard/usbhid.c b/hid_mouse_keyboard/usbhid.c deleted file mode 100644 index 1777a1b..0000000 --- a/hid_mouse_keyboard/usbhid.c +++ /dev/null @@ -1,312 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include -#include -#include -#include -#include -#include -#include - -#include "keycodes.h" - -const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = 0, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5710, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -static const uint8_t hid_report_descriptor[] = -{ - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x02, /* Usage (Mouse) */ - 0xA1, 0x01, /* Collection (Application) */ - 0x09, 0x01, /* Usage (Pointer) */ - 0xA1, 0x00, /* Collection (Physical) */ - 0x85, 0x01, /* Report ID */ - 0x05, 0x09, /* Usage Page (Buttons) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x03, /* Usage Maximum (03) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (0) */ - 0x95, 0x03, /* Report Count (3) */ - 0x75, 0x01, /* Report Size (1) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x05, /* Report Size (5) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x30, /* Usage (X) */ - 0x09, 0x31, /* Usage (Y) */ - 0x15, 0x81, /* Logical Minimum (-127) */ - 0x25, 0x7F, /* Logical Maximum (127) */ - 0x75, 0x08, /* Report Size (8) */ - 0x95, 0x02, /* Report Count (2) */ - 0x81, 0x06, /* Input (Data, Variable, Relative) */ - 0xC0, 0xC0,/* End Collection,End Collection */ -// - 0x09, 0x06, /* Usage (Keyboard) */ - 0xA1, 0x01, /* Collection (Application) */ - 0x85, 0x02, /* Report ID */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0xE0, /* Usage Minimum (224) */ - 0x29, 0xE7, /* Usage Maximum (231) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (1) */ - 0x75, 0x01, /* Report Size (1) */ - 0x95, 0x08, /* Report Count (8) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (8) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x95, 0x05, /* Report Count (5) */ - 0x75, 0x01, /* Report Size (1) */ - 0x05, 0x08, /* Usage Page (Page# for LEDs) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x05, /* Usage Maximum (05) */ - 0x91, 0x02, /* Output (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x03, /* Report Size (3) */ - 0x91, 0x01, /* Output (Constant) */ - 0x95, 0x06, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (3) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x65, /* Logical Maximum (101) */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0x00, /* Usage Minimum (00) */ - 0x29, 0x65, /* Usage Maximum (101) */ - 0x81, 0x00, /* Input (Data, Array) */ - 0xC0 /* End Collection,End Collection */ -}; - -static const struct { - struct usb_hid_descriptor hid_descriptor; - struct { - uint8_t bReportDescriptorType; - uint16_t wDescriptorLength; - } __attribute__((packed)) hid_report; -} __attribute__((packed)) hid_function = { - .hid_descriptor = { - .bLength = sizeof(hid_function), - .bDescriptorType = USB_DT_HID, - .bcdHID = 0x0100, - .bCountryCode = 0, - .bNumDescriptors = 1, - }, - .hid_report = { - .bReportDescriptorType = USB_DT_REPORT, - .wDescriptorLength = sizeof(hid_report_descriptor), - }, -}; - -const struct usb_endpoint_descriptor hid_endpoint = { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x81, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 9, - .bInterval = 0x05, -}; - -const struct usb_interface_descriptor hid_iface = { - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_HID, - .bInterfaceSubClass = 1, // boot - .bInterfaceProtocol = 1, // keyboard - .iInterface = 0, - - .endpoint = &hid_endpoint, - - .extra = &hid_function, - .extralen = sizeof(hid_function), -}; - -const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = &hid_iface, -}}; - -const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 1, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0xC0, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Something strange", - "Keyboard + mouse", - "demo", -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -static int hid_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, - void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)) -{ - (void)complete; - (void)usbd_dev; - - if ((req->bmRequestType != 0x81) || - (req->bRequest != USB_REQ_GET_DESCRIPTOR) || - (req->wValue != 0x2200)) - return 0; - - /* Handle the HID report descriptor. */ - *buf = (uint8_t *)hid_report_descriptor; - *len = sizeof(hid_report_descriptor); - - return 1; -} - -static void hid_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - hid_control_request); - - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); - /* SysTick interrupt every N clock pulses: set reload to N-1 */ - systick_set_reload(99999); - systick_interrupt_enable(); - systick_counter_enable(); -} - -usbd_device *usbd_dev; - -int main(void) -{ - int i; - - rcc_clock_setup_in_hsi_out_48mhz(); - - rcc_periph_clock_enable(RCC_GPIOC); - - gpio_set(GPIOC, GPIO11); - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); - - usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - usbd_register_set_config_callback(usbd_dev, hid_set_config); - - for (i = 0; i < 0x80000; i++) - __asm__("nop"); - - gpio_clear(GPIOC, GPIO11); - - while (1) - usbd_poll(usbd_dev); -} - -void move_mouse(int8_t x, int8_t y){ - /* - * buf[0]: 1 - report ID - * buf[1]: bit2 - middle button, bit1 - right, bit0 - left - * buf[2]: move X - * buf[3]: move Y - * buf[4]: wheel - */ - int8_t buf[5] = {1,0,0,0,0}; - buf[2] = x; buf[3] = y; - while(5 != usbd_ep_write_packet(usbd_dev, 0x81, buf, 5)); -} - -/* - * Keyboard buffer: - * buf[1]: MOD - * buf[2]: reserved - * buf[3]..buf[8] - keycodes 1..6 - */ -void send_word(char *wrd){ - do{ - while(9 != usbd_ep_write_packet(usbd_dev, 0x81, press_key(*wrd), 9)); - while(9 != usbd_ep_write_packet(usbd_dev, 0x81, release_key(), 9)); - }while(*(++wrd)); -} - -void sys_tick_handler(void){ - static int steps = 0; - static uint8_t state = 0; - int8_t x = 0, y = 0; - switch (state){ - case 0: - x = 1; - break; - case 1: - y = 1; - break; - case 2: - x = -1; - break; - default: - y = -1; - break; - } - if(++steps > 40){ - switch (state){ - case 0: - send_word("top right\n"); - break; - case 1: - send_word("bottom right\n"); - break; - case 2: - send_word("bottom left\n"); - break; - default: - send_word("top left\n"); - break; - } - steps = 0; - if(++state == 4) - state = 0; - } - move_mouse(x, y); -} - diff --git a/keyboard_snippet/Makefile b/keyboard_snippet/Makefile deleted file mode 100644 index dcab05a..0000000 --- a/keyboard_snippet/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = keyboard -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DKBD_3BY4 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/keyboard_snippet/Readme.md b/keyboard_snippet/Readme.md deleted file mode 100644 index d2c51d7..0000000 --- a/keyboard_snippet/Readme.md +++ /dev/null @@ -1,4 +0,0 @@ -### USB HID keyboard snippet - -This snippet allows to emulate USB keyboard to send different messages as they where typed on simple keyboard -(usefull for multiplatform usage without any drivers setup) diff --git a/keyboard_snippet/keyboard.bin b/keyboard_snippet/keyboard.bin deleted file mode 100755 index e9996de..0000000 Binary files a/keyboard_snippet/keyboard.bin and /dev/null differ diff --git a/keyboard_snippet/keycodes.c b/keyboard_snippet/keycodes.c deleted file mode 100644 index 7d9d2f5..0000000 --- a/keyboard_snippet/keycodes.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * keycodes.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "keycodes.h" -/* - * Keyboard buffer: - * buf[0]: MOD - * buf[1]: reserved - * buf[2]..buf[7] - keycodes 1..6 - */ -static uint8_t buf[8] = {0,0,0,0,0,0,0,0}; - -#define _(x) (x|0x80) -// array for keycodes according to ASCII table; MSB is MOD_SHIFT flag -static const uint8_t keycodes[] = { - // space !"#$%&' - KEY_SPACE, _(KEY_1), _(KEY_QUOTE), _(KEY_3), _(KEY_4), _(KEY_5), _(KEY_7), KEY_QUOTE, - // ()*+,-./ - _(KEY_9), _(KEY_0), _(KEY_8), _(KEY_EQUAL), KEY_COMMA, KEY_MINUS, KEY_PERIOD, KEY_SLASH, - // 0..9 - 39, 30, 31, 32, 33, 34, 35, 36, 37, 38, - // :;<=>?@ - _(KEY_SEMICOLON), KEY_SEMICOLON, _(KEY_COMMA), KEY_EQUAL, _(KEY_PERIOD), _(KEY_SLASH), _(KEY_2), - // A..Z: for a in $(seq 0 25); do printf "$((a+132)),"; done - 132,133,134,135,136,137,138,139,140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157, - // [\]^_` - KEY_LEFT_BRACE, KEY_BACKSLASH, KEY_RIGHT_BRACE, _(KEY_6), _(KEY_MINUS), KEY_TILDE, - // a..z: for a in $(seq 0 25); do printf "$((a+4)),"; done - 4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29, - // {|}~ - _(KEY_LEFT_BRACE), _(KEY_BACKSLASH), _(KEY_RIGHT_BRACE), _(KEY_TILDE) -}; - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY){ - buf[0] = MOD; - buf[2] = KEY; - return buf; -} - -/** - * return buffer for sending symbol "ltr" with addition modificator mod - */ -uint8_t *press_key_mod(char ltr, uint8_t mod){ - uint8_t MOD = 0; - uint8_t KEY = 0; - if(ltr > 31){ - KEY = keycodes[ltr - 32]; - if(KEY & 0x80){ - MOD = MOD_SHIFT; - KEY &= 0x7f; - } - }else if (ltr == '\n') KEY = KEY_ENTER; - buf[0] = MOD | mod; - buf[2] = KEY; - return buf; -} diff --git a/keyboard_snippet/keycodes.h b/keyboard_snippet/keycodes.h deleted file mode 100644 index 98a2fa1..0000000 --- a/keyboard_snippet/keycodes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* - * keycodes.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __KEYKODES_H__ -#define __KEYKODES_H__ - -#include - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY); -#define release_key() set_key_buf(0,0) -uint8_t *press_key_mod(char key, uint8_t mod); -#define press_key(k) press_key_mod(k, 0) - -#define MOD_CTRL 0x01 -#define MOD_SHIFT 0x02 -#define MOD_ALT 0x04 -#define MOD_GUI 0x08 - -#define LEFT(mod) (mod) -#define RIGHT(mod) ((mod << 4)) - -#define KEY_A 4 -#define KEY_B 5 -#define KEY_C 6 -#define KEY_D 7 -#define KEY_E 8 -#define KEY_F 9 -#define KEY_G 10 -#define KEY_H 11 -#define KEY_I 12 -#define KEY_J 13 -#define KEY_K 14 -#define KEY_L 15 -#define KEY_M 16 -#define KEY_N 17 -#define KEY_O 18 -#define KEY_P 19 -#define KEY_Q 20 -#define KEY_R 21 -#define KEY_S 22 -#define KEY_T 23 -#define KEY_U 24 -#define KEY_V 25 -#define KEY_W 26 -#define KEY_X 27 -#define KEY_Y 28 -#define KEY_Z 29 -#define KEY_1 30 -#define KEY_2 31 -#define KEY_3 32 -#define KEY_4 33 -#define KEY_5 34 -#define KEY_6 35 -#define KEY_7 36 -#define KEY_8 37 -#define KEY_9 38 -#define KEY_0 39 -#define KEY_ENTER 40 -#define KEY_ESC 41 -#define KEY_BACKSPACE 42 -#define KEY_TAB 43 -#define KEY_SPACE 44 -#define KEY_MINUS 45 -#define KEY_EQUAL 46 -#define KEY_LEFT_BRACE 47 -#define KEY_RIGHT_BRACE 48 -#define KEY_BACKSLASH 49 -#define KEY_NUMBER 50 -#define KEY_SEMICOLON 51 -#define KEY_QUOTE 52 -#define KEY_TILDE 53 -#define KEY_COMMA 54 -#define KEY_PERIOD 55 -#define KEY_SLASH 56 -#define KEY_CAPS_LOCK 57 -#define KEY_F1 58 -#define KEY_F2 59 -#define KEY_F3 60 -#define KEY_F4 61 -#define KEY_F5 62 -#define KEY_F6 63 -#define KEY_F7 64 -#define KEY_F8 65 -#define KEY_F9 66 -#define KEY_F10 67 -#define KEY_F11 68 -#define KEY_F12 69 -#define KEY_PRINTSCREEN 70 -#define KEY_SCROLL_LOCK 71 -#define KEY_PAUSE 72 -#define KEY_INSERT 73 -#define KEY_HOME 74 -#define KEY_PAGE_UP 75 -#define KEY_DELETE 76 -#define KEY_END 77 -#define KEY_PAGE_DOWN 78 -#define KEY_RIGHT 79 -#define KEY_LEFT 80 -#define KEY_DOWN 81 -#define KEY_UP 82 -#define KEY_NUM_LOCK 83 -#define KEYPAD_SLASH 84 -#define KEYPAD_ASTERIX 85 -#define KEYPAD_MINUS 86 -#define KEYPAD_PLUS 87 -#define KEYPAD_ENTER 88 -#define KEYPAD_1 89 -#define KEYPAD_2 90 -#define KEYPAD_3 91 -#define KEYPAD_4 92 -#define KEYPAD_5 93 -#define KEYPAD_6 94 -#define KEYPAD_7 95 -#define KEYPAD_8 96 -#define KEYPAD_9 97 -#define KEYPAD_0 98 -#define KEYPAD_PERIOD 99 - -#endif // __KEYKODES_H__ diff --git a/keyboard_snippet/ld/devices.data b/keyboard_snippet/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/keyboard_snippet/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/keyboard_snippet/ld/stm32f103x4.ld b/keyboard_snippet/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/keyboard_snippet/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103x6.ld b/keyboard_snippet/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/keyboard_snippet/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103x8.ld b/keyboard_snippet/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/keyboard_snippet/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xB.ld b/keyboard_snippet/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/keyboard_snippet/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xC.ld b/keyboard_snippet/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/keyboard_snippet/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xD.ld b/keyboard_snippet/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/keyboard_snippet/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xE.ld b/keyboard_snippet/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/keyboard_snippet/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xF.ld b/keyboard_snippet/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/keyboard_snippet/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/ld/stm32f103xG.ld b/keyboard_snippet/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/keyboard_snippet/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/keyboard_snippet/main.c b/keyboard_snippet/main.c deleted file mode 100644 index de15abf..0000000 --- a/keyboard_snippet/main.c +++ /dev/null @@ -1,73 +0,0 @@ -/* - * main.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "ocm.h" -#include "usbkeybrd.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -int main(void){ - uint32_t oldT = 0; - - rcc_clock_setup_in_hsi_out_48mhz(); - SysTick_init(); -/* - // if PC11 connected to usb 1.5kOhm pull-up through transistor - rcc_periph_clock_enable(RCC_GPIOC); - gpio_set(GPIOC, GPIO11); - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); -*/ - usbkeybrd_setup(); -/* - int i; - for (i = 0; i < 0x80000; i++) - __asm__("nop"); - gpio_clear(GPIOC, GPIO11); -*/ - uint32_t seconds_ctr = 0; - while (1){ - poll_usbkeybrd(); - if(Timer - oldT > 999 || oldT > Timer){ - print_int(seconds_ctr++); - newline(); - oldT = Timer; - } - } -} - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - process_usbkbrd(); -} diff --git a/keyboard_snippet/ocm.h b/keyboard_snippet/ocm.h deleted file mode 100644 index b810b4b..0000000 --- a/keyboard_snippet/ocm.h +++ /dev/null @@ -1,34 +0,0 @@ -/* - * ocm.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __OCM_H__ -#define __OCM_H__ - -#include -#include -#include -#include -#include -#include -#include - -#endif // __OCM_H__ diff --git a/keyboard_snippet/usbkeybrd.c b/keyboard_snippet/usbkeybrd.c deleted file mode 100644 index 1a3408c..0000000 --- a/keyboard_snippet/usbkeybrd.c +++ /dev/null @@ -1,270 +0,0 @@ -/* - * usbkeybrd.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "usbkeybrd.h" -#include "keycodes.h" - -#define BUFLEN 512 -static char sendbuf[BUFLEN]; -static char *msg_start = sendbuf, *msg_end = sendbuf; -static const char *buf_end = sendbuf+BUFLEN; - -usbd_device *usbd_dev; - -const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = 0, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, -// 0x03EB 0x2042 - Atmel Keyboard Demo Application - .idVendor = 0x03EB, - .idProduct = 0x2042, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -static const uint8_t hid_report_descriptor[] = { - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x06, /* Usage (Keyboard) */ - 0xA1, 0x01, /* Collection (Application) */ -// 0x85, 0x02, /* Report ID */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0xE0, /* Usage Minimum (224) */ - 0x29, 0xE7, /* Usage Maximum (231) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (1) */ - 0x75, 0x01, /* Report Size (1) */ - 0x95, 0x08, /* Report Count (8) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (8) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x95, 0x05, /* Report Count (5) */ - 0x75, 0x01, /* Report Size (1) */ - 0x05, 0x08, /* Usage Page (Page# for LEDs) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x05, /* Usage Maximum (05) */ - 0x91, 0x02, /* Output (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x03, /* Report Size (3) */ - 0x91, 0x01, /* Output (Constant) */ - 0x95, 0x06, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (3) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x65, /* Logical Maximum (101) */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0x00, /* Usage Minimum (00) */ - 0x29, 0x65, /* Usage Maximum (101) */ - 0x81, 0x00, /* Input (Data, Array) */ - 0x09, 0x05, /* Usage (Vendor Defined) */ - 0x15, 0x00, /* Logical Minimum (0)) */ - 0x26, 0xFF, 0x00, /* Logical Maximum (255)) */ - 0x75, 0x08, /* Report Count (2)) */ - 0x95, 0x02, /* Report Size (8 bit)) */ - 0xB1, 0x02, /* Feature (Data, Variable, Absolute) */ - 0xC0 /* End Collection,End Collection */ -}; - -static const struct { - struct usb_hid_descriptor hid_descriptor; - struct { - uint8_t bReportDescriptorType; - uint16_t wDescriptorLength; - } __attribute__((packed)) hid_report; -} __attribute__((packed)) hid_function = { - .hid_descriptor = { - .bLength = sizeof(hid_function), - .bDescriptorType = USB_DT_HID, - .bcdHID = 0x0100, - .bCountryCode = 0, - .bNumDescriptors = 1, - }, - .hid_report = { - .bReportDescriptorType = USB_DT_REPORT, - .wDescriptorLength = sizeof(hid_report_descriptor), - }, -}; - -const struct usb_endpoint_descriptor hid_endpoint = { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x81, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 8, - .bInterval = 0x10, -}; - -const struct usb_interface_descriptor hid_iface = { - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_HID, - .bInterfaceSubClass = 1, // boot - .bInterfaceProtocol = 1, // keyboard - .iInterface = 0, - - .endpoint = &hid_endpoint, - - .extra = &hid_function, - .extralen = sizeof(hid_function), -}; - -const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = &hid_iface, -}}; - -const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 1, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0xC0, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Simple matrix keyboard 3x4", - "EEV", - "v01", -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -static int hid_control_request(usbd_device *usbddev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, - void (**complete)(usbd_device *usbddev, struct usb_setup_data *req)){ - (void)complete; - (void)usbddev; - - if ((req->bmRequestType != 0x81) || - (req->bRequest != USB_REQ_GET_DESCRIPTOR) || - (req->wValue != 0x2200)) - return 0; - - *buf = (uint8_t *)hid_report_descriptor; - *len = sizeof(hid_report_descriptor); - - return 1; -} - -void hid_set_config(usbd_device *usbddev, uint16_t wValue){ - (void)wValue; - (void)usbddev; - usbd_ep_setup(usbd_dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL); - usbd_register_control_callback( - usbddev, - USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - hid_control_request); -} - -void usbkeybrd_setup(){ - usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - usbd_register_set_config_callback(usbd_dev, hid_set_config); -} - -#define put_char_to_buf(ch) do{*(msg_end++) = ch; if(msg_end == buf_end) msg_end = sendbuf;}while(0) -/** - * put data into keyboard buffer - * THERE's NO DATA CORRUPTION CONTROL HERE!!! - */ -void send_msg(char *msg){ - while(*msg){ - put_char_to_buf(*(msg++)); - } -} - -void newline(){ - put_char_to_buf('\n'); -} - -/** - * send data from keyboard buffer - */ -void process_usbkbrd(){ - static uint8_t pressed = 0; - if(pressed){ // the keyboard was "pressed" - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, release_key(), 8)) - pressed = 0; - }else if(msg_start != msg_end){ // we need to send keypress event - if(8 == usbd_ep_write_packet(usbd_dev, 0x81, press_key(*msg_start), 8)){ - if(++msg_start == buf_end) - msg_start = sendbuf; - pressed = 1; - } - }else return; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - inline void putc(char c){ - if(c < 10) - put_char_to_buf(c + '0'); - else - put_char_to_buf(c + 'a' - 10); - } - put_char_to_buf('0'); - put_char_to_buf('x'); - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - char buf[10]; - int32_t L = 0; - if(N < 0){ - put_char_to_buf('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) put_char_to_buf(buf[L]); - }else put_char_to_buf('0'); -} - diff --git a/keyboard_snippet/usbkeybrd.h b/keyboard_snippet/usbkeybrd.h deleted file mode 100644 index 0e074b1..0000000 --- a/keyboard_snippet/usbkeybrd.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * usbkeybrd.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USBKEYBRD_H__ -#define __USBKEYBRD_H__ - -#include "ocm.h" - -extern usbd_device *usbd_dev; - -void process_usbkbrd(); -void send_msg(char *msg); -#define P(x) send_msg(x) -void usbkeybrd_setup(); - -void print_hex(uint8_t *buff, uint8_t l); -void print_int(int32_t N); - -void newline(); - -#define poll_usbkeybrd() usbd_poll(usbd_dev) - -#endif // __USBKEYBRD_H__ diff --git a/matrix_keyboard/Makefile b/matrix_keyboard/Makefile deleted file mode 100644 index 54a6dbd..0000000 --- a/matrix_keyboard/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = matrkeyb -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103xB.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DKBD_3BY4 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/matrix_keyboard/Readme.md b/matrix_keyboard/Readme.md deleted file mode 100644 index 1bb611c..0000000 --- a/matrix_keyboard/Readme.md +++ /dev/null @@ -1,6 +0,0 @@ -### USB HID keyboard - -This is an emulator allowing to connect simple matrix -keyboard 3x3 or 4x4 to computer as regular USB keyboard - -To choose type of keyboard define KBD_3BY4 or KBD_4BY4 in Makefile diff --git a/matrix_keyboard/keycodes.c b/matrix_keyboard/keycodes.c deleted file mode 100644 index 7d9d2f5..0000000 --- a/matrix_keyboard/keycodes.c +++ /dev/null @@ -1,74 +0,0 @@ -/* - * keycodes.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "keycodes.h" -/* - * Keyboard buffer: - * buf[0]: MOD - * buf[1]: reserved - * buf[2]..buf[7] - keycodes 1..6 - */ -static uint8_t buf[8] = {0,0,0,0,0,0,0,0}; - -#define _(x) (x|0x80) -// array for keycodes according to ASCII table; MSB is MOD_SHIFT flag -static const uint8_t keycodes[] = { - // space !"#$%&' - KEY_SPACE, _(KEY_1), _(KEY_QUOTE), _(KEY_3), _(KEY_4), _(KEY_5), _(KEY_7), KEY_QUOTE, - // ()*+,-./ - _(KEY_9), _(KEY_0), _(KEY_8), _(KEY_EQUAL), KEY_COMMA, KEY_MINUS, KEY_PERIOD, KEY_SLASH, - // 0..9 - 39, 30, 31, 32, 33, 34, 35, 36, 37, 38, - // :;<=>?@ - _(KEY_SEMICOLON), KEY_SEMICOLON, _(KEY_COMMA), KEY_EQUAL, _(KEY_PERIOD), _(KEY_SLASH), _(KEY_2), - // A..Z: for a in $(seq 0 25); do printf "$((a+132)),"; done - 132,133,134,135,136,137,138,139,140,141,142,143,144,145,146,147,148,149,150,151,152,153,154,155,156,157, - // [\]^_` - KEY_LEFT_BRACE, KEY_BACKSLASH, KEY_RIGHT_BRACE, _(KEY_6), _(KEY_MINUS), KEY_TILDE, - // a..z: for a in $(seq 0 25); do printf "$((a+4)),"; done - 4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29, - // {|}~ - _(KEY_LEFT_BRACE), _(KEY_BACKSLASH), _(KEY_RIGHT_BRACE), _(KEY_TILDE) -}; - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY){ - buf[0] = MOD; - buf[2] = KEY; - return buf; -} - -/** - * return buffer for sending symbol "ltr" with addition modificator mod - */ -uint8_t *press_key_mod(char ltr, uint8_t mod){ - uint8_t MOD = 0; - uint8_t KEY = 0; - if(ltr > 31){ - KEY = keycodes[ltr - 32]; - if(KEY & 0x80){ - MOD = MOD_SHIFT; - KEY &= 0x7f; - } - }else if (ltr == '\n') KEY = KEY_ENTER; - buf[0] = MOD | mod; - buf[2] = KEY; - return buf; -} diff --git a/matrix_keyboard/keycodes.h b/matrix_keyboard/keycodes.h deleted file mode 100644 index 98a2fa1..0000000 --- a/matrix_keyboard/keycodes.h +++ /dev/null @@ -1,138 +0,0 @@ -/* - * keycodes.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __KEYKODES_H__ -#define __KEYKODES_H__ - -#include - -uint8_t *set_key_buf(uint8_t MOD, uint8_t KEY); -#define release_key() set_key_buf(0,0) -uint8_t *press_key_mod(char key, uint8_t mod); -#define press_key(k) press_key_mod(k, 0) - -#define MOD_CTRL 0x01 -#define MOD_SHIFT 0x02 -#define MOD_ALT 0x04 -#define MOD_GUI 0x08 - -#define LEFT(mod) (mod) -#define RIGHT(mod) ((mod << 4)) - -#define KEY_A 4 -#define KEY_B 5 -#define KEY_C 6 -#define KEY_D 7 -#define KEY_E 8 -#define KEY_F 9 -#define KEY_G 10 -#define KEY_H 11 -#define KEY_I 12 -#define KEY_J 13 -#define KEY_K 14 -#define KEY_L 15 -#define KEY_M 16 -#define KEY_N 17 -#define KEY_O 18 -#define KEY_P 19 -#define KEY_Q 20 -#define KEY_R 21 -#define KEY_S 22 -#define KEY_T 23 -#define KEY_U 24 -#define KEY_V 25 -#define KEY_W 26 -#define KEY_X 27 -#define KEY_Y 28 -#define KEY_Z 29 -#define KEY_1 30 -#define KEY_2 31 -#define KEY_3 32 -#define KEY_4 33 -#define KEY_5 34 -#define KEY_6 35 -#define KEY_7 36 -#define KEY_8 37 -#define KEY_9 38 -#define KEY_0 39 -#define KEY_ENTER 40 -#define KEY_ESC 41 -#define KEY_BACKSPACE 42 -#define KEY_TAB 43 -#define KEY_SPACE 44 -#define KEY_MINUS 45 -#define KEY_EQUAL 46 -#define KEY_LEFT_BRACE 47 -#define KEY_RIGHT_BRACE 48 -#define KEY_BACKSLASH 49 -#define KEY_NUMBER 50 -#define KEY_SEMICOLON 51 -#define KEY_QUOTE 52 -#define KEY_TILDE 53 -#define KEY_COMMA 54 -#define KEY_PERIOD 55 -#define KEY_SLASH 56 -#define KEY_CAPS_LOCK 57 -#define KEY_F1 58 -#define KEY_F2 59 -#define KEY_F3 60 -#define KEY_F4 61 -#define KEY_F5 62 -#define KEY_F6 63 -#define KEY_F7 64 -#define KEY_F8 65 -#define KEY_F9 66 -#define KEY_F10 67 -#define KEY_F11 68 -#define KEY_F12 69 -#define KEY_PRINTSCREEN 70 -#define KEY_SCROLL_LOCK 71 -#define KEY_PAUSE 72 -#define KEY_INSERT 73 -#define KEY_HOME 74 -#define KEY_PAGE_UP 75 -#define KEY_DELETE 76 -#define KEY_END 77 -#define KEY_PAGE_DOWN 78 -#define KEY_RIGHT 79 -#define KEY_LEFT 80 -#define KEY_DOWN 81 -#define KEY_UP 82 -#define KEY_NUM_LOCK 83 -#define KEYPAD_SLASH 84 -#define KEYPAD_ASTERIX 85 -#define KEYPAD_MINUS 86 -#define KEYPAD_PLUS 87 -#define KEYPAD_ENTER 88 -#define KEYPAD_1 89 -#define KEYPAD_2 90 -#define KEYPAD_3 91 -#define KEYPAD_4 92 -#define KEYPAD_5 93 -#define KEYPAD_6 94 -#define KEYPAD_7 95 -#define KEYPAD_8 96 -#define KEYPAD_9 97 -#define KEYPAD_0 98 -#define KEYPAD_PERIOD 99 - -#endif // __KEYKODES_H__ diff --git a/matrix_keyboard/ld/devices.data b/matrix_keyboard/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/matrix_keyboard/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/matrix_keyboard/ld/stm32f103x4.ld b/matrix_keyboard/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/matrix_keyboard/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103x6.ld b/matrix_keyboard/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/matrix_keyboard/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103x8.ld b/matrix_keyboard/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/matrix_keyboard/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xB.ld b/matrix_keyboard/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/matrix_keyboard/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xC.ld b/matrix_keyboard/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/matrix_keyboard/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xD.ld b/matrix_keyboard/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/matrix_keyboard/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xE.ld b/matrix_keyboard/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/matrix_keyboard/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xF.ld b/matrix_keyboard/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/matrix_keyboard/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/ld/stm32f103xG.ld b/matrix_keyboard/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/matrix_keyboard/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/matrix_keyboard/main.c b/matrix_keyboard/main.c deleted file mode 100644 index ac2a932..0000000 --- a/matrix_keyboard/main.c +++ /dev/null @@ -1,277 +0,0 @@ -/* - * main.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include -#include -#include -#include -#include -#include -#include - -#include "keycodes.h" -#include "matrixkbd.h" - -const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = 0, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, -// 0x03EB 0x2042 - Atmel Keyboard Demo Application - .idVendor = 0x03EB, - .idProduct = 0x2042, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -static const uint8_t hid_report_descriptor[] = { - 0x05, 0x01, /* Usage Page (Generic Desktop) */ - 0x09, 0x06, /* Usage (Keyboard) */ - 0xA1, 0x01, /* Collection (Application) */ -// 0x85, 0x02, /* Report ID */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0xE0, /* Usage Minimum (224) */ - 0x29, 0xE7, /* Usage Maximum (231) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x01, /* Logical Maximum (1) */ - 0x75, 0x01, /* Report Size (1) */ - 0x95, 0x08, /* Report Count (8) */ - 0x81, 0x02, /* Input (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (8) */ - 0x81, 0x01, /* Input (Constant) ;5 bit padding */ - 0x95, 0x05, /* Report Count (5) */ - 0x75, 0x01, /* Report Size (1) */ - 0x05, 0x08, /* Usage Page (Page# for LEDs) */ - 0x19, 0x01, /* Usage Minimum (01) */ - 0x29, 0x05, /* Usage Maximum (05) */ - 0x91, 0x02, /* Output (Data, Variable, Absolute) */ - 0x95, 0x01, /* Report Count (1) */ - 0x75, 0x03, /* Report Size (3) */ - 0x91, 0x01, /* Output (Constant) */ - 0x95, 0x06, /* Report Count (1) */ - 0x75, 0x08, /* Report Size (3) */ - 0x15, 0x00, /* Logical Minimum (0) */ - 0x25, 0x65, /* Logical Maximum (101) */ - 0x05, 0x07, /* Usage (Key codes) */ - 0x19, 0x00, /* Usage Minimum (00) */ - 0x29, 0x65, /* Usage Maximum (101) */ - 0x81, 0x00, /* Input (Data, Array) */ - 0x09, 0x05, /* Usage (Vendor Defined) */ - 0x15, 0x00, /* Logical Minimum (0)) */ - 0x26, 0xFF, 0x00, /* Logical Maximum (255)) */ - 0x75, 0x08, /* Report Count (2)) */ - 0x95, 0x02, /* Report Size (8 bit)) */ - 0xB1, 0x02, /* Feature (Data, Variable, Absolute) */ - 0xC0 /* End Collection,End Collection */ -}; -#if 0 - 0x05, 0x01, // Usage Page (Generic Desktop), - 0x09, 0x06, // Usage (Keyboard), - 0xA1, 0x01, // Collection (Application), - 0x75, 0x01, // Report Size (1), - 0x95, 0x08, // Report Count (8), - 0x05, 0x07, // Usage Page (Key Codes), - 0x19, 0xE0, // Usage Minimum (224), - 0x29, 0xE7, // Usage Maximum (231), - 0x15, 0x00, // Logical Minimum (0), - 0x25, 0x01, // Logical Maximum (1), - 0x81, 0x02, // Input (Data, Variable, Absolute), ;Modifier byte - 0x95, 0x01, // Report Count (1), - 0x75, 0x08, // Report Size (8), - 0x81, 0x03, // Input (Constant), ;Reserved byte - 0x95, 0x05, // Report Count (5), - 0x75, 0x01, // Report Size (1), - 0x05, 0x08, // Usage Page (LEDs), - 0x19, 0x01, // Usage Minimum (1), - 0x29, 0x05, // Usage Maximum (5), - 0x91, 0x02, // Output (Data, Variable, Absolute), ;LED report - 0x95, 0x01, // Report Count (1), - 0x75, 0x03, // Report Size (3), - 0x91, 0x03, // Output (Constant), ;LED report padding - 0x95, 0x06, // Report Count (6), - 0x75, 0x08, // Report Size (8), - 0x15, 0x00, // Logical Minimum (0), - 0x25, 0x68, // Logical Maximum(104), - 0x05, 0x07, // Usage Page (Key Codes), - 0x19, 0x00, // Usage Minimum (0), - 0x29, 0x68, // Usage Maximum (104), - 0x81, 0x00, // Input (Data, Array), - 0xc0 // End Collection -}; -#endif - -static const struct { - struct usb_hid_descriptor hid_descriptor; - struct { - uint8_t bReportDescriptorType; - uint16_t wDescriptorLength; - } __attribute__((packed)) hid_report; -} __attribute__((packed)) hid_function = { - .hid_descriptor = { - .bLength = sizeof(hid_function), - .bDescriptorType = USB_DT_HID, - .bcdHID = 0x0100, - .bCountryCode = 0, - .bNumDescriptors = 1, - }, - .hid_report = { - .bReportDescriptorType = USB_DT_REPORT, - .wDescriptorLength = sizeof(hid_report_descriptor), - }, -}; - -const struct usb_endpoint_descriptor hid_endpoint = { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x81, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 8, - .bInterval = 0x10, -}; - -const struct usb_interface_descriptor hid_iface = { - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_HID, - .bInterfaceSubClass = 1, // boot - .bInterfaceProtocol = 1, // keyboard - .iInterface = 0, - - .endpoint = &hid_endpoint, - - .extra = &hid_function, - .extralen = sizeof(hid_function), -}; - -const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = &hid_iface, -}}; - -const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 1, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0xC0, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Simple matrix keyboard 3x4", - "EEV", - "v01", -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -static int hid_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, uint16_t *len, - void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)usbd_dev; - - if ((req->bmRequestType != 0x81) || - (req->bRequest != USB_REQ_GET_DESCRIPTOR) || - (req->wValue != 0x2200)) - return 0; - - *buf = (uint8_t *)hid_report_descriptor; - *len = sizeof(hid_report_descriptor); - - return 1; -} - -static void hid_set_config(usbd_device *usbd_dev, uint16_t wValue){ - (void)wValue; - (void)usbd_dev; - usbd_ep_setup(usbd_dev, 0x81, USB_ENDPOINT_ATTR_INTERRUPT, 4, NULL); - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_STANDARD | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - hid_control_request); -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -int main(void){ - usbd_device *usbd_dev; - - rcc_clock_setup_in_hsi_out_48mhz(); - SysTick_init(); -/* - // if PC11 connected to usb 1.5kOhm pull-up through transistor - rcc_periph_clock_enable(RCC_GPIOC); - gpio_set(GPIOC, GPIO11); - gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, GPIO11); -*/ - usbd_dev = usbd_init(&stm32f103_usb_driver, &dev, &config, usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - usbd_register_set_config_callback(usbd_dev, hid_set_config); - matrixkbd_init(); -/* - int i; - for (i = 0; i < 0x80000; i++) - __asm__("nop"); - gpio_clear(GPIOC, GPIO11); -*/ - - while (1){ - char prsd, rlsd; - usbd_poll(usbd_dev); - get_matrixkbd(&prsd, &rlsd); - if(rlsd) - while(8 != usbd_ep_write_packet(usbd_dev, 0x81, release_key(), 8)); - if(prsd) - while(8 != usbd_ep_write_packet(usbd_dev, 0x81, press_key(prsd), 8)); - } -} - -volatile uint32_t Timer = 0; // global timer (milliseconds) -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; -} diff --git a/matrix_keyboard/matrixkbd.c b/matrix_keyboard/matrixkbd.c deleted file mode 100644 index 8e17654..0000000 --- a/matrix_keyboard/matrixkbd.c +++ /dev/null @@ -1,119 +0,0 @@ -/* - * matrixkbd.c - * Simple utilite for working with matrix keyboard 3columns x 4rows - * Don't understand multiple keys!!! - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "matrixkbd.h" - -extern volatile uint32_t Timer; - -#if !defined(KBD_3BY4) && !defined(KBD_4BY4) - #error You should define keyboard type: KBD_3BY4 or KBD_4BY4 -#endif - -/* - * Rows are inputs, columns are outputs - */ -#define ROWS 4 -const uint32_t row_ports[ROWS] = {ROW1_PORT, ROW2_PORT, ROW3_PORT, ROW4_PORT}; -const uint16_t row_pins[ROWS] = {ROW1_PIN, ROW2_PIN, ROW3_PIN, ROW4_PIN}; -// symbols[Rows][Columns] -#if defined(KBD_3BY4) -#define COLS 3 -const uint32_t col_ports[COLS] = {COL1_PORT, COL2_PORT, COL3_PORT}; -const uint16_t col_pins[COLS] = {COL1_PIN, COL2_PIN, COL3_PIN}; -char kbd[ROWS][COLS] = { - {'1', '2', '3'}, - {'4', '5', '6'}, - {'7', '8', '9'}, - {'*', '0', '#'} -}; -#elif defined(KBD_4BY4) -#define COLS 4 -const uint32_t col_ports[COLS] = {COL1_PORT, COL2_PORT, COL3_PORT, COL4_PORT}; -const uint16_t col_pins[COLS] = {COL1_PIN, COL2_PIN, COL3_PIN, COL4_PIN}; -char kbd[ROWS][COLS] = { - {'1', '2', '3', 'A'}, - {'4', '5', '6', 'B'}, - {'7', '8', '9', 'C'}, - {'*', '0', '#', 'D'} -}; -#endif -uint8_t oldstate[ROWS][COLS]; - -/** - * init keyboard pins: all columns are opendrain outputs - * all rows are pullup inputs - */ -void matrixkbd_init(){ - int i, j; - rcc_peripheral_enable_clock(&RCC_APB2ENR, KBD_RCC_PORT_CLOCK); - for(i = 0; i < COLS; ++i){ - gpio_set(col_ports[i], col_pins[i]); - gpio_set_mode(col_ports[i], GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - col_pins[i]); - } - for(i = 0; i < ROWS; ++i){ - gpio_set(row_ports[i], row_pins[i]); - gpio_set_mode(row_ports[i], GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - row_pins[i]); - } - for(j = 0; j < ROWS; ++j) - for(i = 0; i < COLS; ++i) - oldstate[j][i] = 1; -} - - -/** - * Check keyboard - * if some key pressed, set prsd to its value (symbol) - * if released - set rlsd to 1 - * works onse per 60ms - * DON't work with multiple key pressing! - * In case of simultaneous pressing it will return at first call code of - * first key met, at second - second and so on - */ -void get_matrixkbd(char *prsd, char *rlsd){ - *prsd = 0; - *rlsd = 0; - static uint32_t oldTimer = 0; - if(Timer > oldTimer && Timer - oldTimer < KBD_TIMEOUT) return; - int r, c; - for(c = 0; c < COLS; ++c){ - gpio_clear(col_ports[c], col_pins[c]); - oldTimer = Timer; - while(oldTimer == Timer); // wait at least one second - for(r = 0; r < ROWS; ++r){ - uint8_t st = (gpio_get(row_ports[r], row_pins[r])) ? 1 : 0; - if(oldstate[r][c] != st){ // button state changed - oldstate[r][c] = st; - gpio_set(col_ports[c], col_pins[c]); - if(st == 1){ // released - *rlsd = 1; - }else{ - *prsd = kbd[r][c]; - } - return; - } - } - gpio_set(col_ports[c], col_pins[c]); - } -} diff --git a/matrix_keyboard/matrixkbd.h b/matrix_keyboard/matrixkbd.h deleted file mode 100644 index 408c5c2..0000000 --- a/matrix_keyboard/matrixkbd.h +++ /dev/null @@ -1,52 +0,0 @@ -/* - * matrixkbd.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include -#include -#include -#include - -void matrixkbd_init(); -void get_matrixkbd(char *prsd, char *rlsd); - -// timeout for keyboard checkout -#define KBD_TIMEOUT 50 - -// kbd ports for clock_enable -#define KBD_RCC_PORT_CLOCK (RCC_APB2ENR_IOPAEN | RCC_APB2ENR_IOPBEN) -// Rows pins & ports: PB15, 13, 11 & 10 -#define ROW1_PORT (GPIOB) -#define ROW1_PIN (GPIO15) -#define ROW2_PORT (GPIOB) -#define ROW2_PIN (GPIO13) -#define ROW3_PORT (GPIOB) -#define ROW3_PIN (GPIO11) -#define ROW4_PORT (GPIOB) -#define ROW4_PIN (GPIO10) -// Columns pins & ports: PB1, PA7 & PA5 -#define COL1_PORT (GPIOB) -#define COL1_PIN (GPIO1) -#define COL2_PORT (GPIOA) -#define COL2_PIN (GPIO7) -#define COL3_PORT (GPIOA) -#define COL3_PIN (GPIO5) -//#define COL4_PORT () -//#define COL4_PIN () diff --git a/matrix_keyboard/matrkeyb.bin b/matrix_keyboard/matrkeyb.bin deleted file mode 100755 index 29ce3c4..0000000 Binary files a/matrix_keyboard/matrkeyb.bin and /dev/null differ diff --git a/nokia5110/Makefile b/nokia5110/Makefile deleted file mode 100644 index 2c582f9..0000000 --- a/nokia5110/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = nokia5110 -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/nokia5110/cdcacm.c b/nokia5110/cdcacm.c deleted file mode 100644 index 6354836..0000000 --- a/nokia5110/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "SAO RAS, Emelianov E.V.", - "Nokia 5110 control", - "0.1", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/nokia5110/cdcacm.h b/nokia5110/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/nokia5110/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/nokia5110/font.c b/nokia5110/font.c deleted file mode 100644 index a43a4c7..0000000 --- a/nokia5110/font.c +++ /dev/null @@ -1,260 +0,0 @@ -/* - * font.c - russian font - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "font.h" - -const U8 rusfont [] = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,// 32 [0x20] - - 0x00, 0x00, 0x5F, 0x00, 0x00, 0x00,// 33 [0x21] - ! - 0x00, 0x07, 0x00, 0x07, 0x00, 0x00,// 34 [0x22] - " - 0x14, 0x7F, 0x14, 0x7F, 0x14, 0x00,// 35 [0x23] - # - 0x24, 0x2A, 0x7F, 0x2A, 0x12, 0x00,// 36 [0x24] - $ - 0x23, 0x13, 0x08, 0x64, 0x62, 0x00,// 37 [0x25] - % - 0x36, 0x49, 0x55, 0x22, 0x50, 0x00,// 38 [0x26] - & - 0x00, 0x05, 0x03, 0x00, 0x00, 0x00,// 39 [0x27] - ' - 0x00, 0x1C, 0x22, 0x41, 0x00, 0x00,// 40 [0x28] - ( - 0x00, 0x41, 0x22, 0x1C, 0x00, 0x00,// 41 [0x29] - ) - 0x08, 0x2A, 0x1C, 0x2A, 0x08, 0x00,// 42 [0x2a] - * - 0x08, 0x08, 0x3E, 0x08, 0x08, 0x00,// 43 [0x2b] - + - 0x00, 0x50, 0x30, 0x00, 0x00, 0x00,// 44 [0x2c] - , - 0x08, 0x08, 0x08, 0x08, 0x08, 0x00,// 45 [0x2d] - - - 0x00, 0x60, 0x60, 0x00, 0x00, 0x00,// 46 [0x2e] - . - 0x20, 0x10, 0x08, 0x04, 0x02, 0x00,// 47 [0x2f] - / - 0x3E, 0x51, 0x49, 0x45, 0x3E, 0x00,// 48 [0x30] - 0 - 0x00, 0x42, 0x7F, 0x40, 0x00, 0x00,// 49 [0x31] - 1 - 0x42, 0x61, 0x51, 0x49, 0x46, 0x00,// 50 [0x32] - 2 - 0x21, 0x41, 0x45, 0x4B, 0x31, 0x00,// 51 [0x33] - 3 - 0x18, 0x14, 0x12, 0x7F, 0x10, 0x00,// 52 [0x34] - 4 - 0x27, 0x45, 0x45, 0x45, 0x39, 0x00,// 53 [0x35] - 5 - 0x3C, 0x4A, 0x49, 0x49, 0x30, 0x00,// 54 [0x36] - 6 - 0x01, 0x71, 0x09, 0x05, 0x03, 0x00,// 55 [0x37] - 7 - 0x36, 0x49, 0x49, 0x49, 0x36, 0x00,// 56 [0x38] - 8 - 0x06, 0x49, 0x49, 0x29, 0x1E, 0x00,// 57 [0x39] - 9 - 0x00, 0x36, 0x36, 0x00, 0x00, 0x00,// 58 [0x3a] - : - 0x00, 0x56, 0x36, 0x00, 0x00, 0x00,// 59 [0x3b] - ; - 0x00, 0x08, 0x14, 0x22, 0x41, 0x00,// 60 [0x3c] - < - 0x14, 0x14, 0x14, 0x14, 0x14, 0x00,// 61 [0x3d] - = - 0x41, 0x22, 0x14, 0x08, 0x00, 0x00,// 62 [0x3e] - > - 0x02, 0x01, 0x51, 0x09, 0x06, 0x00,// 63 [0x3f] - ? - 0x32, 0x49, 0x79, 0x41, 0x3E, 0x00,// 64 [0x40] - @ - 0x7E, 0x11, 0x11, 0x11, 0x7E, 0x00,// 65 [0x41] - A - 0x7F, 0x49, 0x49, 0x49, 0x36, 0x00,// 66 [0x42] - B - 0x3E, 0x41, 0x41, 0x41, 0x22, 0x00,// 67 [0x43] - C - 0x7F, 0x41, 0x41, 0x22, 0x1C, 0x00,// 68 [0x44] - D - 0x7F, 0x49, 0x49, 0x49, 0x41, 0x00,// 69 [0x45] - E - 0x7F, 0x09, 0x09, 0x01, 0x01, 0x00,// 70 [0x46] - F - 0x3E, 0x41, 0x41, 0x51, 0x32, 0x00,// 71 [0x47] - G - 0x7F, 0x08, 0x08, 0x08, 0x7F, 0x00,// 72 [0x48] - H - 0x00, 0x41, 0x7F, 0x41, 0x00, 0x00,// 73 [0x49] - I - 0x20, 0x40, 0x41, 0x3F, 0x01, 0x00,// 74 [0x4a] - J - 0x7F, 0x08, 0x14, 0x22, 0x41, 0x00,// 75 [0x4b] - K - 0x7F, 0x40, 0x40, 0x40, 0x40, 0x00,// 76 [0x4c] - L - 0x7F, 0x02, 0x04, 0x02, 0x7F, 0x00,// 77 [0x4d] - M - 0x7F, 0x04, 0x08, 0x10, 0x7F, 0x00,// 78 [0x4e] - N - 0x3E, 0x41, 0x41, 0x41, 0x3E, 0x00,// 79 [0x4f] - O - 0x7F, 0x09, 0x09, 0x09, 0x06, 0x00,// 80 [0x50] - P - 0x3e, 0x41, 0x51, 0x21, 0xde, 0x00,// 81 [0x51] - Q - 0x7F, 0x09, 0x19, 0x29, 0x46, 0x00,// 82 [0x52] - R - 0x46, 0x49, 0x49, 0x49, 0x31, 0x00,// 83 [0x53] - S - 0x01, 0x01, 0x7F, 0x01, 0x01, 0x00,// 84 [0x54] - T - 0x3F, 0x40, 0x40, 0x40, 0x3F, 0x00,// 85 [0x55] - U - 0x1F, 0x20, 0x40, 0x20, 0x1F, 0x00,// 86 [0x56] - V - 0x7F, 0x20, 0x18, 0x20, 0x7F, 0x00,// 87 [0x57] - W - 0x63, 0x14, 0x08, 0x14, 0x63, 0x00,// 88 [0x58] - X - 0x03, 0x04, 0x78, 0x04, 0x03, 0x00,// 89 [0x59] - Y - 0x61, 0x51, 0x49, 0x45, 0x43, 0x00,// 90 [0x5a] - Z - 0x00, 0x00, 0x7F, 0x41, 0x41, 0x00,// 91 [0x5b] - [ - 0x02, 0x04, 0x08, 0x10, 0x20, 0x00,// 92 [0x5c] - "\" - 0x41, 0x41, 0x7F, 0x00, 0x00, 0x00,// 93 [0x5d] - ] - 0x04, 0x02, 0x01, 0x02, 0x04, 0x00,// 94 [0x5e] - ^ - 0x40, 0x40, 0x40, 0x40, 0x40, 0x00,// 95 [0x5f] - _ - 0x00, 0x01, 0x02, 0x04, 0x00, 0x00,// 96 [0x60] - ` - 0x20, 0x54, 0x54, 0x54, 0x78, 0x00,// 97 [0x61] - a - 0x7F, 0x48, 0x44, 0x44, 0x38, 0x00,// 98 [0x62] - b - 0x38, 0x44, 0x44, 0x44, 0x20, 0x00,// 99 [0x63] - c - 0x38, 0x44, 0x44, 0x48, 0x7F, 0x00,//100 [0x64] - d - 0x38, 0x54, 0x54, 0x54, 0x18, 0x00,//101 [0x65] - e - 0x00, 0x08, 0xfe, 0x09, 0x02, 0x00,//102 [0x66] - f - 0x18, 0xa4, 0xa4, 0x94, 0x78, 0x00,//103 [0x67] - g - 0x7F, 0x08, 0x04, 0x04, 0x78, 0x00,//104 [0x68] - h - 0x00, 0x44, 0x7D, 0x40, 0x00, 0x00,//105 [0x69] - i - 0x40, 0x80, 0x84, 0x7d, 0x00, 0x00,//106 [0x6a] - j - 0x00, 0x7F, 0x10, 0x28, 0x44, 0x00,//107 [0x6b] - k - 0x00, 0x41, 0x7F, 0x40, 0x00, 0x00,//108 [0x6c] - l - 0x7C, 0x04, 0x18, 0x04, 0x78, 0x00,//109 [0x6d] - m - 0x7C, 0x08, 0x04, 0x04, 0x78, 0x00,//110 [0x6e] - n - 0x38, 0x44, 0x44, 0x44, 0x38, 0x00,//111 [0x6f] - o - 0xfc, 0x28, 0x24, 0x24, 0x18, 0x00,//112 [0x70] - p - 0x18, 0x24, 0x24, 0x28, 0xfc, 0x00,//113 [0x71] - q - 0x7C, 0x08, 0x04, 0x04, 0x08, 0x00,//114 [0x72] - r - 0x48, 0x54, 0x54, 0x54, 0x20, 0x00,//115 [0x73] - s - 0x04, 0x3F, 0x44, 0x40, 0x20, 0x00,//116 [0x74] - t - 0x3C, 0x40, 0x40, 0x20, 0x7C, 0x00,//117 [0x75] - u - 0x1C, 0x20, 0x40, 0x20, 0x1C, 0x00,//118 [0x76] - v - 0x3C, 0x40, 0x30, 0x40, 0x3C, 0x00,//119 [0x77] - w - 0x44, 0x28, 0x10, 0x28, 0x44, 0x00,//120 [0x78] - x - 0x0C, 0x50, 0x50, 0x50, 0x3C, 0x00,//121 [0x79] - y - 0x44, 0x64, 0x54, 0x4C, 0x44, 0x00,//122 [0x7a] - z - 0x00, 0x08, 0x36, 0x41, 0x00, 0x00,//123 [0x7b] - { - 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00,//124 [0x7c] - | - 0x00, 0x41, 0x36, 0x08, 0x00, 0x00,//125 [0x7d] - } - 0x08, 0x04, 0x08, 0x10, 0x08, 0x00,//126 [0x7e] - ~ - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,//127 [0x7f] - - 0x08, 0x08, 0x08, 0x08, 0x08, 0x08,//128 [0x80] - € - 0x00, 0x00, 0xff, 0x00, 0x00, 0x00,//129 [0x81] - - 0x00, 0x00, 0xf8, 0x08, 0x08, 0x08,//130 [0x82] - ‚ - 0x08, 0x08, 0xf8, 0x00, 0x00, 0x00,//131 [0x83] - ƒ - 0x00, 0x00, 0x0f, 0x08, 0x08, 0x08,//132 [0x84] - „ - 0x08, 0x08, 0x0f, 0x00, 0x00, 0x00,//133 [0x85] - … - 0x00, 0x00, 0xff, 0x08, 0x08, 0x08,//134 [0x86] - † - 0x08, 0x08, 0xff, 0x00, 0x00, 0x00,//135 [0x87] - ‡ - 0x08, 0x08, 0xf8, 0x08, 0x08, 0x08,//136 [0x88] - ˆ - 0x08, 0x08, 0x0f, 0x08, 0x08, 0x08,//137 [0x89] - ‰ - 0x08, 0x08, 0xff, 0x08, 0x08, 0x08,//138 [0x8a] - Š - 0x0f, 0x0f, 0x0f, 0x0f, 0x0f, 0x0f,//139 [0x8b] - ‹ - 0xf0, 0xf0, 0xf0, 0xf0, 0xf0, 0xf0,//140 [0x8c] - Œ - 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,//141 [0x8d] - - 0xff, 0xff, 0xff, 0x00, 0x00, 0x00,//142 [0x8e] - Ž - 0x00, 0x00, 0x00, 0xff, 0xff, 0xff,//143 [0x8f] - - 0x00, 0xaa, 0x00, 0x55, 0x00, 0xaa,//144 [0x90] - - 0x55, 0xaa, 0x55, 0xaa, 0x55, 0xaa,//145 [0x91] - ‘ - 0x55, 0xff, 0x55, 0xff, 0x55, 0xff,//146 [0x92] - ’ - 0x00, 0x00, 0xfc, 0x02, 0x04, 0x00,//147 [0x93] - “ - 0x3c, 0x3c, 0x3c, 0x3c, 0x3c, 0x3c,//148 [0x94] - ” - 0x00, 0x00, 0x18, 0x18, 0x00, 0x00,//149 [0x95] - • - 0x08, 0x38, 0x40, 0x30, 0x0e, 0x01,//150 [0x96] - – - 0x24, 0x12, 0x24, 0x48, 0x24, 0x00,//151 [0x97] - — - 0x00, 0x44, 0x4a, 0x51, 0x00, 0x00,//152 [0x98] - ˜ - 0x00, 0x51, 0x4a, 0x44, 0x00, 0x00,//153 [0x99] - ™ - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,//154 [0x9a] - š - 0x20, 0x40, 0x3f, 0x00, 0x00, 0x00,//155 [0x9b] - › - 0x00, 0x06, 0x09, 0x06, 0x00, 0x00,//156 [0x9c] - œ - 0x00, 0x0d, 0x0b, 0x00, 0x00, 0x00,//157 [0x9d] - - 0x00, 0x00, 0x08, 0x00, 0x00, 0x00,//158 [0x9e] - ž - 0x08, 0x08, 0x2a, 0x08, 0x08, 0x00,//159 [0x9f] - Ÿ - 0x14, 0x14, 0x14, 0x14, 0x14, 0x14,//160 [0xa0] -   - 0x00, 0xff, 0x00, 0xff, 0x00, 0x00,//161 [0xa1] - ¡ - 0x00, 0x00, 0xfc, 0x14, 0x14, 0x14,//162 [0xa2] - ¢ - 0x38, 0x55, 0x54, 0x55, 0x18, 0x00,//163 [0xa3] - £ - 0x00, 0xf8, 0x08, 0xf8, 0x08, 0x08,//164 [0xa4] - ¤ - 0x00, 0xfc, 0x04, 0xf4, 0x14, 0x14,//165 [0xa5] - ¥ - 0x14, 0x14, 0xfc, 0x00, 0x00, 0x00,//166 [0xa6] - ¦ - 0x08, 0xf8, 0x08, 0xf8, 0x00, 0x00,//167 [0xa7] - § - 0x14, 0xf4, 0x04, 0xfc, 0x00, 0x00,//168 [0xa8] - ¨ - 0x00, 0x00, 0x1f, 0x14, 0x14, 0x14,//169 [0xa9] - © - 0x00, 0x0f, 0x08, 0x0f, 0x08, 0x08,//170 [0xaa] - ª - 0x00, 0x1f, 0x10, 0x17, 0x14, 0x14,//171 [0xab] - « - 0x14, 0x14, 0x1f, 0x00, 0x00, 0x00,//172 [0xac] - ¬ - 0x08, 0x0f, 0x08, 0x0f, 0x00, 0x00,//173 [0xad] - ­ - 0x14, 0x17, 0x10, 0x1f, 0x00, 0x00,//174 [0xae] - ® - 0x00, 0x00, 0xff, 0x14, 0x14, 0x14,//175 [0xaf] - ¯ - 0x00, 0xff, 0x00, 0xff, 0x08, 0x08,//176 [0xb0] - ° - 0x00, 0xff, 0x00, 0xf7, 0x14, 0x14,//177 [0xb1] - ± - 0x14, 0x14, 0xff, 0x00, 0x00, 0x00,//178 [0xb2] - ² - 0x7e, 0x4b, 0x4a, 0x43, 0x42, 0x00,//179 [0xb3] - ³ - 0x08, 0xff, 0x00, 0xff, 0x00, 0x00,//180 [0xb4] - ´ - 0x14, 0xf7, 0x00, 0xff, 0x00, 0x00,//181 [0xb5] - µ - 0x14, 0x14, 0xf4, 0x14, 0x14, 0x14,//182 [0xb6] - ¶ - 0x08, 0xf8, 0x08, 0xf8, 0x08, 0x08,//183 [0xb7] - · - 0x14, 0xf4, 0x04, 0xf4, 0x14, 0x14,//184 [0xb8] - ¸ - 0x14, 0x14, 0x17, 0x14, 0x14, 0x14,//185 [0xb9] - ¹ - 0x08, 0x0f, 0x08, 0x0f, 0x08, 0x08,//186 [0xba] - º - 0x14, 0x17, 0x14, 0x17, 0x14, 0x14,//187 [0xbb] - » - 0x14, 0x14, 0xff, 0x14, 0x14, 0x14,//188 [0xbc] - ¼ - 0x08, 0xff, 0x08, 0xff, 0x08, 0x08,//189 [0xbd] - ½ - 0x14, 0xf7, 0x00, 0xf7, 0x14, 0x14,//190 [0xbe] - ¾ - 0x3e, 0x5d, 0x55, 0x41, 0x3e, 0x00,//191 [0xbf] - ¿ - 0x7c, 0x10, 0x38, 0x44, 0x38, 0x00,//192 [0xc0] - À - 0x20, 0x54, 0x54, 0x54, 0x78, 0x00,//193 [0xc1] - Á - 0x3c, 0x4a, 0x4a, 0x49, 0x31, 0x00,//194 [0xc2] -  - 0x7c, 0x40, 0x40, 0x40, 0xfc, 0x00,//195 [0xc3] - à - 0xe0, 0x54, 0x4c, 0x44, 0xfc, 0x00,//196 [0xc4] - Ä - 0x38, 0x54, 0x54, 0x54, 0x18, 0x00,//197 [0xc5] - Å - 0x30, 0x48, 0xfc, 0x48, 0x30, 0x00,//198 [0xc6] - Æ - 0x7c, 0x04, 0x04, 0x04, 0x0c, 0x00,//199 [0xc7] - Ç - 0x44, 0x28, 0x10, 0x28, 0x44, 0x00,//200 [0xc8] - È - 0x7c, 0x20, 0x10, 0x08, 0x7c, 0x00,//201 [0xc9] - É - 0x7c, 0x41, 0x22, 0x11, 0x7c, 0x00,//202 [0xca] - Ê - 0x7c, 0x10, 0x28, 0x44, 0x00, 0x00,//203 [0xcb] - Ë - 0x20, 0x44, 0x3c, 0x04, 0x7c, 0x00,//204 [0xcc] - Ì - 0x7c, 0x08, 0x10, 0x08, 0x7c, 0x00,//205 [0xcd] - Í - 0x7c, 0x10, 0x10, 0x10, 0x7c, 0x00,//206 [0xce] - Î - 0x38, 0x44, 0x44, 0x44, 0x38, 0x00,//207 [0xcf] - Ï - 0x7c, 0x04, 0x04, 0x04, 0x7c, 0x00,//208 [0xd0] - Ð - 0x08, 0x54, 0x34, 0x14, 0x7c, 0x00,//209 [0xd1] - Ñ - 0x7C, 0x14, 0x14, 0x14, 0x08, 0x00,//210 [0xd2] - Ò - 0x38, 0x44, 0x44, 0x44, 0x20, 0x00,//211 [0xd3] - Ó - 0x04, 0x04, 0x7c, 0x04, 0x04, 0x00,//212 [0xd4] - Ô - 0x0C, 0x50, 0x50, 0x50, 0x3C, 0x00,//213 [0xd5] - Õ - 0x6c, 0x10, 0x7c, 0x10, 0x6c, 0x00,//214 [0xd6] - Ö - 0x7c, 0x54, 0x54, 0x28, 0x00, 0x00,//215 [0xd7] - × - 0x7c, 0x50, 0x50, 0x20, 0x00, 0x00,//216 [0xd8] - Ø - 0x7c, 0x50, 0x50, 0x20, 0x7c, 0x00,//217 [0xd9] - Ù - 0x44, 0x44, 0x54, 0x54, 0x28, 0x00,//218 [0xda] - Ú - 0x7c, 0x40, 0x7c, 0x40, 0x7c, 0x00,//219 [0xdb] - Û - 0x28, 0x44, 0x54, 0x54, 0x38, 0x00,//220 [0xdc] - Ü - 0x7c, 0x40, 0x7c, 0x40, 0xfc, 0x00,//221 [0xdd] - Ý - 0x0c, 0x10, 0x10, 0x10, 0x7c, 0x00,//222 [0xde] - Þ - 0x04, 0x7c, 0x50, 0x50, 0x20, 0x00,//223 [0xdf] - ß - 0x7f, 0x08, 0x3e, 0x41, 0x3e, 0x00,//224 [0xe0] - à - 0x7e, 0x11, 0x11, 0x11, 0x7e, 0x00,//225 [0xe1] - á - 0x7f, 0x49, 0x49, 0x49, 0x33, 0x00,//226 [0xe2] - â - 0x7f, 0x40, 0x40, 0x40, 0xff, 0x00,//227 [0xe3] - ã - 0xe0, 0x51, 0x4f, 0x41, 0xff, 0x00,//228 [0xe4] - ä - 0x7f, 0x49, 0x49, 0x49, 0x41, 0x00,//229 [0xe5] - å - 0x1c, 0x22, 0x7f, 0x22, 0x1c, 0x00,//230 [0xe6] - æ - 0x7f, 0x01, 0x01, 0x01, 0x03, 0x00,//231 [0xe7] - ç - 0x63, 0x14, 0x08, 0x14, 0x63, 0x00,//232 [0xe8] - è - 0x7f, 0x10, 0x08, 0x04, 0x7f, 0x00,//233 [0xe9] - é - 0x7c, 0x21, 0x12, 0x09, 0x7c, 0x00,//234 [0xea] - ê - 0x7f, 0x08, 0x14, 0x22, 0x41, 0x00,//235 [0xeb] - ë - 0x20, 0x41, 0x3f, 0x01, 0x7f, 0x00,//236 [0xec] - ì - 0x7f, 0x02, 0x0c, 0x02, 0x7f, 0x00,//237 [0xed] - í - 0x7f, 0x08, 0x08, 0x08, 0x7f, 0x00,//238 [0xee] - î - 0x3e, 0x41, 0x41, 0x41, 0x3e, 0x00,//239 [0xef] - ï - 0x7f, 0x01, 0x01, 0x01, 0x7f, 0x00,//240 [0xf0] - ð - 0x46, 0x29, 0x19, 0x09, 0x7f, 0x00,//241 [0xf1] - ñ - 0x7f, 0x09, 0x09, 0x09, 0x06, 0x00,//242 [0xf2] - ò - 0x3e, 0x41, 0x41, 0x41, 0x22, 0x00,//243 [0xf3] - ó - 0x01, 0x01, 0x7f, 0x01, 0x01, 0x00,//244 [0xf4] - ô - 0x47, 0x28, 0x10, 0x08, 0x07, 0x00,//245 [0xf5] - õ - 0x77, 0x08, 0x7f, 0x08, 0x77, 0x00,//246 [0xf6] - ö - 0x7f, 0x49, 0x49, 0x49, 0x36, 0x00,//247 [0xf7] - ÷ - 0x22, 0x41, 0x49, 0x49, 0x3e, 0x00,//248 [0xf8] - ø - 0x7f, 0x48, 0x30, 0x00, 0x7f, 0x00,//249 [0xf9] - ù - 0x41, 0x49, 0x49, 0x49, 0x36, 0x00,//250 [0xfa] - ú - 0x7f, 0x40, 0x7f, 0x40, 0x7f, 0x00,//251 [0xfb] - û - 0x00, 0x7f, 0x48, 0x48, 0x30, 0x00,//252 [0xfc] - ü - 0x7f, 0x40, 0x7f, 0x40, 0xff, 0x00,//253 [0xfd] - ý - 0x07, 0x08, 0x08, 0x08, 0x7f, 0x00,//254 [0xfe] - þ - 0x01, 0x7f, 0x48, 0x48, 0x30, 0x00,//255 [0xff] - ÿ -}; - -/** - * Return letter array - */ -const U8 *letter(U8 koi8){ - U16 idx; - if(koi8 < 32) koi8 = 32; - idx = (koi8 - 32) * LTR_WIDTH; - return &rusfont[idx]; -} - diff --git a/nokia5110/font.h b/nokia5110/font.h deleted file mode 100644 index d92a747..0000000 --- a/nokia5110/font.h +++ /dev/null @@ -1,32 +0,0 @@ -/* - * font.h - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __FONT_H__ -#define __FONT_H__ -#include -typedef uint8_t U8; -typedef uint16_t U16; - -#define LTR_WIDTH (6) - -const U8 *letter(U8 koi8); - -#endif // __FONT_H__ diff --git a/nokia5110/hw_init.c b/nokia5110/hw_init.c deleted file mode 100644 index 4faaf21..0000000 --- a/nokia5110/hw_init.c +++ /dev/null @@ -1,51 +0,0 @@ -/* - * hw_init.c - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#include "hw_init.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); - // LCD pins: DC, SCE, RST - gpio_set_mode(DC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, DC_PIN | SCE_PIN | RST_PIN); -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - - diff --git a/nokia5110/hw_init.h b/nokia5110/hw_init.h deleted file mode 100644 index d09cedf..0000000 --- a/nokia5110/hw_init.h +++ /dev/null @@ -1,74 +0,0 @@ -/* - * hw_init.h - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __HW_INIT_H__ -#define __HW_INIT_H__ - -#include "main.h" - -/* - * USB interface - */ -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() - -void GPIO_init(); -void SysTick_init(); - -/* here are functions & macros for changing command pins state: - * SET_DC() - set D/~C pin high (data) - * CLEAR_DC() - clear D/~C (command) - * CHIP_EN() - clear ~SCE - * CHIP_DIS() - set ~SCE (disable chip) - * CLEAR_RST() - set 1 on RST pin - * LCD_RST() - set 0 on RST pin - */ -/* pins: - * DC: PB6 - * SCE: PB7 - * RST: PB8 - */ -#define DC_PORT GPIOB -#define SCE_PORT GPIOB -#define RST_PORT GPIOB -#define DC_PIN GPIO6 -#define SCE_PIN GPIO7 -#define RST_PIN GPIO8 - -#define SET_DC() do{GPIO_BSRR(DC_PORT) = DC_PIN;}while(0) -#define CLEAR_DC() do{GPIO_BSRR(DC_PORT) = DC_PIN << 16;}while(0) -#define CHIP_EN() do{GPIO_BSRR(SCE_PORT) = SCE_PIN << 16;}while(0) -#define CHIP_DIS() do{GPIO_BSRR(SCE_PORT) = SCE_PIN;}while(0) -#define CLEAR_RST() do{GPIO_BSRR(RST_PORT) = RST_PIN;}while(0) -#define LCD_RST() do{GPIO_BSRR(RST_PORT) = RST_PIN << 16;}while(0) - -#endif // __HW_INIT_H__ diff --git a/nokia5110/ld/devices.data b/nokia5110/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/nokia5110/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/nokia5110/ld/stm32f103x4.ld b/nokia5110/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/nokia5110/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103x6.ld b/nokia5110/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/nokia5110/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103x8.ld b/nokia5110/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/nokia5110/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xB.ld b/nokia5110/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/nokia5110/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xC.ld b/nokia5110/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/nokia5110/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xD.ld b/nokia5110/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/nokia5110/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xE.ld b/nokia5110/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/nokia5110/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xF.ld b/nokia5110/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/nokia5110/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/ld/stm32f103xG.ld b/nokia5110/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/nokia5110/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/nokia5110/main.c b/nokia5110/main.c deleted file mode 100644 index b026cba..0000000 --- a/nokia5110/main.c +++ /dev/null @@ -1,107 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hw_init.h" -#include "spi.h" -#include "cdcacm.h" -#include "pcd8544.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} - - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - - switch_SPI(SPI1); - SPI_init(); - pcd8544_init(); - - usb_connect(); // turn on USB - - pcd8544_print((uint8_t*)"÷ÓÅ × ÐÏÒÑÄËÅ\n\nAll OK\n"); - - uint8_t wb; - int i; - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ - for(i = 0; i < usbdatalen; ++i){ - uint8_t rb = (uint8_t)usbdatabuf[i]; - wb = pcd8544_putch(rb); - if(wb == rb){ - pcd8544_roll_screen(); - wb = pcd8544_putch(rb); - } - if(wb != rb){ - usb_send(rb); - if(wb == '\n') usb_send('\n'); - } - } - usbdatalen = 0; - } - //check_and_parse_UART(USART1); // also check data in UART buffers - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - //print_int(Timer / 1000);newline(); - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} diff --git a/nokia5110/main.h b/nokia5110/main.h deleted file mode 100644 index 9218551..0000000 --- a/nokia5110/main.h +++ /dev/null @@ -1,52 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/nokia5110/nokia5110.bin b/nokia5110/nokia5110.bin deleted file mode 100755 index 7677467..0000000 Binary files a/nokia5110/nokia5110.bin and /dev/null differ diff --git a/nokia5110/pcd8544.c b/nokia5110/pcd8544.c deleted file mode 100644 index 896020a..0000000 --- a/nokia5110/pcd8544.c +++ /dev/null @@ -1,236 +0,0 @@ -/* - * pcd8544.c - functions for work with display controller - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * we have two modes: direct write into LCD (with local buffer update) - for text - * and refresh whole buffer - for graphics - * all writings are in horizontal addressing mode - */ - -#include "pcd8544.h" -// here should be functions spiWrite(U8 *data, bufsz_t size) & spi_write_byte(U8 onebyte) -// max SPI speed is 4MHz -#include "spi.h" -/* here are functions & macros for changing command pins state: - * SET_DC() - set D/~C pin high (data) - * CLEAR_DC() - clear D/~C (command) - * CHIP_EN() - clear ~SCE - * CHIP_DIS() - set ~SCE (disable chip) - * CLEAR_RST() - set 1 on RST pin - * LCD_RST() - set 0 on RST pin - */ -#include "hw_init.h" -#include - -const scrnsz_t LTRS_IN_ROW = XSIZE / LTR_WIDTH; -const scrnsz_t ROW_MAX = YSIZE / 8; -// array for fast pixel set/reset -const U8 const pixels_set[] = {1,2,4,8,0x10,0x20,0x40,0x80}; -const U8 const pixels_reset[] = {0xfe,0xfd,0xfb,0xf7,0xef,0xdf,0xbf,0x7f}; -/** - * I use horizontal addressing of PCD8544, so data in buffer - * stored line by line, each byte is 8 vertical pixels (LSB upper) - * - * As refresh speed is fast enough, I don't use partial update for graphics - * (but use for letters) - */ -#define DISPLAYBUFSIZE (XSIZE*YCHARSZ) -static U8 displaybuf[DISPLAYBUFSIZE]; - -// current letter coordinates - for "printf" -static scrnsz_t cur_x = 0, cur_y = 0; -extern U8 bias, vop, temp; - -void pcd8544_setbias(U8 val){ - CMD(PCD8544_EXTENDEDINSTRUCTION); - SETBIAS(val); - CMD(PCD8544_DEFAULTMODE); -} - -void pcd8544_setvop(U8 val){ - CMD(PCD8544_EXTENDEDINSTRUCTION); - SETVOP(val); - CMD(PCD8544_DEFAULTMODE); -} - -void pcd8544_settemp(U8 val){ - CMD(PCD8544_EXTENDEDINSTRUCTION); - SETTEMP(val); - CMD(PCD8544_DEFAULTMODE); -} - -/** - * Init SPI & display - */ -void pcd8544_init(){ - CHIP_DIS(); - SET_DC(); - LCD_RST(); - Delay(10); - CLEAR_RST(); // set ~RST to 1, performing out of RESET stage -// CMD(0x21); CMD(0xc8); CMD(0x06); CMD(0x13); CMD(0x20); CMD(0x0c); - - // set LCD to optimal mode by datasheet: bias 1/48 (n=4), Vlcd 6.06 (Vop=50), normal Tcorr (1) - CMD(PCD8544_EXTENDEDINSTRUCTION); - SETBIAS(4); - SETVOP(65); - SETTEMP(1); - // return to regular instructions set, horizontal addressing & prepare normal display mode - CMD(PCD8544_DEFAULTMODE); - CMD(PCD8544_DISPLAYNORMAL); - - pcd8544_cls(); -} - -/** - * Send command (cmd != 0) or data (cmd == 0) byte - */ -void pcd8544_send_byte(U8 byte, U8 cmd){ - CHIP_EN(); - if(cmd) - CLEAR_DC(); - else - SET_DC(); - spi_write_byte(byte); -} - -/** - * Send data sequence - */ -void pcd8544_send_data(U8 *data, bufsz_t size, U8 cmd){ - CHIP_EN(); - if(cmd) - CLEAR_DC(); - else - SET_DC(); - spiWrite(data, size); - CHIP_DIS(); -} - -void draw_pixel(scrnsz_t x, scrnsz_t y, U8 set){ - bufsz_t idx; - if(bad_coords(x,y)) return; - idx = x + (y/8) * XSIZE; - y %= 8; - if(set) - displaybuf[idx] |= pixels_set[y]; - else - displaybuf[idx] &= pixels_reset[y]; -} - -void pcd8544_cls(){ - memset(displaybuf, 0, DISPLAYBUFSIZE); - cur_x = cur_y = 0; - pcd8544_refresh(); -} - -/** - * send full data buffer onto display - */ -void pcd8544_refresh(){ - SETXADDR(0); - SETYADDR(0); - DBUF(displaybuf, DISPLAYBUFSIZE); -} - -/** - * draw letter at x,y position in char coordinates (XCHARSZ x YCHARSZ) - * @return 0 if fail - */ -int pcd8544_put(U8 koi8, scrnsz_t x, scrnsz_t y){ - U8 *symbol; - bufsz_t idx; - if(x >= XCHARSZ || y >= YCHARSZ) return 0; - if(koi8 < 32) return 0; - symbol = (U8*)letter(koi8); - x *= LTR_WIDTH; - idx = x + y*XSIZE; - // put letter into display buffer - memcpy(&displaybuf[idx], symbol, LTR_WIDTH); - // and show it on display - SETXADDR(x); - SETYADDR(y); - DBUF(symbol, LTR_WIDTH); - return 1; -} - -/** - * put char into current position or next line; return char if couldn't be printed - * (if OK return 0 or '\n' if newline was made) - */ -U8 pcd8544_putch(U8 chr){ - scrnsz_t tabpos; - U8 ret = 0; - if(cur_x >= XCHARSZ || cur_y >= YCHARSZ) return chr; - if(chr < 32){ // special symbols - switch(chr){ - case '\n': // carriage return - return to beginning of current line - ++cur_y; - // here shouldn't be a "break" because '\n' == "\r\n" - case '\r': // newline - cur_x = 0; - break; - case '\b': // return to previous position (backspace) - if(cur_x) --cur_x; - break; - case '\t': // tabulation by 4 symbols - tabpos = ((cur_x>>2)<<2) + 4; - if(tabpos < XCHARSZ) cur_x = tabpos; - else return chr; - break; - } - }else{ - // increment x position here (there could be not writeable letters) - pcd8544_put(chr, cur_x++, cur_y); - } - if(cur_x == XCHARSZ){ - cur_x = 0; - ++cur_y; - return '\n'; - } - return ret; -} - -/** - * print zero-terminated string from current (cur_x, cur_y) - * truncate long strings that don't fit into display - * @return NULL if all OK or pointer to non-printed string - */ -U8 *pcd8544_print(U8 *koi8){ - while(*koi8){ - U8 chr = *koi8; - if(pcd8544_putch(chr) == chr) return koi8; - ++koi8; - } - return NULL; -} - -/** - * roll screen by 1 line up - */ -void pcd8544_roll_screen(){ - bufsz_t idx = DISPLAYBUFSIZE-XSIZE; - memmove(displaybuf, displaybuf + XSIZE, idx); - memset(displaybuf+idx, 0, XSIZE); - pcd8544_refresh(); - if(cur_y) --cur_y; -} - diff --git a/nokia5110/pcd8544.h b/nokia5110/pcd8544.h deleted file mode 100644 index 36fbab2..0000000 --- a/nokia5110/pcd8544.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * pcd8544.h - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __PCD8544_H__ -#define __PCD8544_H__ - -#include "font.h" - -// sizes in graphics (84x48) & char(letter 6x8 -> 14x6) mode -#define XSIZE (84) -#define XCHARSZ (XSIZE/LTR_WIDTH) -#define YSIZE (48) -#define YCHARSZ (YSIZE/8) - -// type of screen size -typedef U8 scrnsz_t; -// type of screen buffer index (scrnsz_t^2) -typedef U16 bufsz_t; - -extern const scrnsz_t LTRS_IN_ROW; -extern const scrnsz_t ROW_MAX; - -#define bad_coords(x, y) (!(x < XSIZE && y < YSIZE)) -#define bad_text_coords(col, row) (!(col < LTRS_IN_ROW && row < ROW_MAX)) - -/* -// bounding box -typedef struct{ - scrnsz_t xmin, - scrnsz_t ymin, - scrnsz_t xmax, - scrnsz_t ymax -} bbox_t; -*/ - -void pcd8544_init(); -void pcd8544_send_byte(U8 byte, U8 cmd); -void pcd8544_send_data(U8 *data, bufsz_t size, U8 cmd); -void draw_pixel(scrnsz_t x, scrnsz_t y, U8 set); -void pcd8544_cls(); -void pcd8544_refresh(); -int pcd8544_put(U8 koi8, scrnsz_t x, scrnsz_t y); -U8 *pcd8544_print(U8 *koi8); -U8 pcd8544_putch(U8 koi8); -void pcd8544_roll_screen(); - -void pcd8544_setbias(U8 val); -void pcd8544_setvop(U8 val); -void pcd8544_settemp(U8 val); - -#define set_pixel(x,y) do{draw_pixel(x,y,1);}while(0) -#define clear_pixel(x,y) do{draw_pixel(x,y,0);}while(0) - -/********************** PCD8544 protocol **********************/ -// Function set: | 0 | 0 | 1 | 0 | 0 | PD | V | H | -#define PCD8544_POWERDOWN (0x24) -#define PCD8544_VERTADDRESSING (0x22) -#define PCD8544_EXTENDEDINSTRUCTION (0x21) -#define PCD8544_DEFAULTMODE (0x20) -/* - * functions with H=0 (basic) - */ -// Display control: | 0 | 0 | 0 | 0 | 1 | D | 0 | E | -#define PCD8544_DISPLAYBLANK (8) -#define PCD8544_DISPLAYFILLED (9) -#define PCD8544_DISPLAYNORMAL (0xc) -#define PCD8544_DISPLAYINVERTED (0xd) -// Set Xaddr: | 1 | X6 | X5 | X4 | X3 | X2 | X1 | X0 | -#define PCD8544_SETXADDR (0x80) -#define PCD8544_XADDR_MASK (0x7f) -// Set Yaddr: | 0 | 1 | 0 | 0 | 0 | Y2 | Y1 | Y0 | -#define PCD8544_SETYADDR (0x40) -#define PCD8544_YADDR_MASK (7) -/* - * functions with H=1 (extended) - */ -// Temperature control: | 0 | 0 | 0 | 0 | 0 | 1 | TC1 | TC0 | -#define PCD8544_SETTEMP (4) -#define PCD8544_TEMP_MASK (3) -// BIAS: | 0 | 0 | 0 | 1 | 0 | BS2 | BS1 | BS0 | -#define PCD8544_SETBIAS (0x10) -#define PCD8544_BIAS_MASK (7) -// VOP: | 1 | VOP6 | VOP5 | VOP4 | VOP3 | VOP2 | VOP1 | VOP0 | -#define PCD8544_SETVOP (0x80) -#define PCD8544_VOP_MASK (0x7f) -// | 0 | 0 | 0 | 0 | 0 | 0 | 0 | 0 | - -/********************** Shortened macros **********************/ -#define CMD(x) do{pcd8544_send_byte(x, 1);}while(0) -#define DAT(x) do{pcd8544_send_byte(x, 0);}while(0) -#define CBUF(x,l) do{pcd8544_send_data(x, l, 1);}while(0) -#define DBUF(x,l) do{pcd8544_send_data(x, l, 0);}while(0) -// set bias level (look into datasheet, 4 - recommend) -#define SETBIAS(x) CMD(PCD8544_SETBIAS|(x&PCD8544_BIAS_MASK)) -// set operation voltage (=3.06+0.06*x) -#define SETVOP(x) CMD(PCD8544_SETVOP |(x&PCD8544_VOP_MASK)) -// temperature compensation: 0 - high, 1 - recommended, 2 - IC, 3 - minimal -#define SETTEMP(x) CMD(PCD8544_SETTEMP|(x&PCD8544_TEMP_MASK)) -// x,y addressing -#define SETXADDR(x) CMD(PCD8544_SETXADDR|(x&PCD8544_XADDR_MASK)) -#define SETYADDR(x) CMD(PCD8544_SETYADDR|(x&PCD8544_YADDR_MASK)) -#endif // __PCD8544_H__ diff --git a/nokia5110/spi.c b/nokia5110/spi.c deleted file mode 100644 index 8d7abb2..0000000 --- a/nokia5110/spi.c +++ /dev/null @@ -1,175 +0,0 @@ -/* - * spi.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "spi.h" -#include "hw_init.h" - -uint32_t Current_SPI = SPI1; // this is SPI interface which would b -/** - * Set current SPI to given value - */ -void switch_SPI(uint32_t SPI){ - Current_SPI = SPI; -} - -/* - * Configure SPI ports - */ -/* - * SPI1 remapped: - * SCK - PB3 - * MISO - PB4 - * MOSI - PB5 - */ -void SPI1_init(){ - // enable AFIO & other clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, - RCC_APB2ENR_SPI1EN | RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - // remap SPI1 (change pins from PA5..7 to PB3..5); also turn off JTAG - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_SPI1_REMAP); - // SCK, MOSI - push-pull output - gpio_set_mode(GPIO_BANK_SPI1_RE_SCK, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_SCK); - gpio_set_mode(GPIO_BANK_SPI1_RE_MOSI, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI1_RE_MOSI); - // MISO - opendrain in - gpio_set_mode(GPIO_BANK_SPI1_RE_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI1_RE_MISO); - spi_reset(SPI1); - /* Set up SPI in Master mode with: - * Clock baud rate: 1/128 of peripheral clock frequency (APB2, 72MHz) - * Clock polarity: CPOL=0, CPHA=0 - * Data frame format: 8-bit - * Frame format: MSB First - */ - spi_init_master(SPI1, SPI_CR1_BAUDRATE_FPCLK_DIV_256, SPI_CR1_CPOL_CLK_TO_0_WHEN_IDLE, - SPI_CR1_CPHA_CLK_TRANSITION_1, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST); - nvic_enable_irq(NVIC_SPI1_IRQ); // enable SPI interrupt - spi_enable(Current_SPI); -} - -/* - * SPI2: - * SCK - PB13 - * MISO - PB14 - * MOSI - PB15 - */ -void SPI2_init(){ - // turn on clocking - //rcc_periph_clock_enable(RCC_SPI2 | RCC_GPIOB); - rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_SPI2EN); - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - // SCK, MOSI - push-pull output - gpio_set_mode(GPIO_BANK_SPI2_SCK, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_SCK); - gpio_set_mode(GPIO_BANK_SPI2_MOSI, GPIO_MODE_OUTPUT_50_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_SPI2_MOSI); - // MISO - opendrain in - gpio_set_mode(GPIO_BANK_SPI2_MISO, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT, GPIO_SPI2_MISO); - spi_reset(SPI2); - /* Set up SPI in Master mode with: - * Clock baud rate: 1/64 of peripheral clock frequency (APB1, 36MHz) - * Clock polarity: Idle High - * Clock phase: Data valid on 2nd clock pulse - * Data frame format: 8-bit - * Frame format: MSB First - */ - spi_init_master(SPI2, SPI_CR1_BAUDRATE_FPCLK_DIV_64, SPI_CR1_CPOL_CLK_TO_0_WHEN_IDLE, - SPI_CR1_CPHA_CLK_TRANSITION_1, SPI_CR1_DFF_8BIT, SPI_CR1_MSBFIRST); -// nvic_enable_irq(NVIC_SPI2_IRQ); // enable SPI interrupt - spi_enable(Current_SPI); -} - -void SPI_init(){ - switch(Current_SPI){ - case SPI1: - SPI1_init(); - break; - case SPI2: - SPI2_init(); - break; - default: - return; // error - } -} - -/** - * send 1 byte blocking - * return 1 on success - */ -uint8_t spi_write_byte(uint8_t data){ - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - SPI_DR(Current_SPI) = data; - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - while(!(SPI_SR(Current_SPI) & SPI_SR_RXNE)); - (void)SPI_DR(Current_SPI); - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - while(SPI_SR(Current_SPI) & SPI_SR_BSY); - return 1; -} - -/** - * Blocking rite data to current SPI - * @param data - buffer with data - * @param len - buffer length - * @return 0 in case of error (or 1 in case of success) - */ -uint8_t spiWrite(uint8_t *data, uint16_t len){ - uint16_t i; - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - for(i = 0; i < len; ++i){ - SPI_DR(Current_SPI) = data[i]; - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - } - while(!(SPI_SR(Current_SPI) & SPI_SR_RXNE)); - (void)SPI_DR(Current_SPI); - while(!(SPI_SR(Current_SPI) & SPI_SR_TXE)); - while(SPI_SR(Current_SPI) & SPI_SR_BSY); - return 1; -} - -/* -// SPI interrupt -void spi_isr(uint32_t spi){ - // TX empty - if(SPI_SR(spi) & SPI_SR_TXE){ - if(SPI_TxIndex < SPI_datalen){ // buffer still not sent fully - // Send Transaction data - SPI_DR(spi) = SPI_TxBuffer[SPI_TxIndex++]; - }else{ // disable TXE interrupt + set EOT flag - spi_disable_tx_buffer_empty_interrupt(spi); - //spi_disable(spi); - SPI_EOT_FLAG = 1; - while(SPI_SR(spi) & SPI_SR_BSY); - } - } - SPI_SR(spi) = 0; // clear all interrupt flags -} - -// interrupts for SPI1 & SPI2 -void spi1_isr(){ - spi_isr(SPI1); -} - -void spi2_isr(){ - spi_isr(SPI2); -} -*/ diff --git a/nokia5110/spi.h b/nokia5110/spi.h deleted file mode 100644 index b0b2767..0000000 --- a/nokia5110/spi.h +++ /dev/null @@ -1,33 +0,0 @@ -/* - * spi.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SPI_H__ -#define __SPI_H__ - -void SPI_init(); -uint8_t spiWrite(uint8_t *data, uint16_t len); -extern uint32_t Current_SPI; -uint8_t spi_write_byte(uint8_t data); - -void switch_SPI(uint32_t SPI); - -#endif // __SPI_H__ diff --git a/nokia5110/sync.c b/nokia5110/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/nokia5110/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/nokia5110/sync.h b/nokia5110/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/nokia5110/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/nokia5110/user_proto.c b/nokia5110/user_proto.c deleted file mode 100644 index 2a18b9b..0000000 --- a/nokia5110/user_proto.c +++ /dev/null @@ -1,103 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hw_init.h" -#include "pcd8544.h" - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer when a full string comes - * return 0 if buffer processed or len if there's not enough data in buffer - */ -/* -void parse_incoming_buf(uint8_t *buf, int len){ - int curpos; - uint8_t *strbeg = buf; - for(curpos = 0; curpos < len; ++curpos){ - if(buf[curpos] == '\n'){ - buf[curpos] = 0; - pcd8544_print(strbeg); - P(strbeg); - P(" printed!\n"); - strbeg = &buf[curpos + 1]; - } - } -}*/ - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/nokia5110/user_proto.h b/nokia5110/user_proto.h deleted file mode 100644 index 63059cd..0000000 --- a/nokia5110/user_proto.h +++ /dev/null @@ -1,45 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -//void parse_incoming_buf(uint8_t *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/simple_cdc/Makefile b/simple_cdc/Makefile deleted file mode 100644 index 9f5db65..0000000 --- a/simple_cdc/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = usb_cdc_simple -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103xB.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/simple_cdc/README b/simple_cdc/README deleted file mode 100644 index 1acf5bf..0000000 --- a/simple_cdc/README +++ /dev/null @@ -1,5 +0,0 @@ -Very simple USB-CDC - -written for chinese devboard based on STM32F103RBT6 - -Press H for help \ No newline at end of file diff --git a/simple_cdc/cdcacm.c b/simple_cdc/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/simple_cdc/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/simple_cdc/cdcacm.h b/simple_cdc/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/simple_cdc/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/simple_cdc/hardware_ini.c b/simple_cdc/hardware_ini.c deleted file mode 100644 index ee3e0d7..0000000 --- a/simple_cdc/hardware_ini.c +++ /dev/null @@ -1,94 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -// check buttons S2/S3 -void check_btns(){ - static uint8_t oldstate[2] = {1,1}; // old buttons state - uint8_t newstate[2], i; - static uint32_t Old_timer[2] = {0,0}; - newstate[0] = gpio_get(BTNS_PORT, BTN_S2_PIN) ? 1 : 0; - newstate[1] = gpio_get(BTNS_PORT, BTN_S3_PIN) ? 1 : 0; - for(i = 0; i < 2; i++){ - uint8_t new = newstate[i]; - // pause for 60ms - uint32_t O = Old_timer[i]; - if(!O){ - if(Timer - O > 60 || O > Timer){ - P("Button S"); - usb_send('2' + i); - if(new) P("released"); - else P("pressed"); - newline(); - oldstate[i] = new; - Old_timer[i] = 0; - } - } - else if(new != oldstate[i]){ - Old_timer[i] = Timer; - } - } -} diff --git a/simple_cdc/hardware_ini.h b/simple_cdc/hardware_ini.h deleted file mode 100644 index ff0311f..0000000 --- a/simple_cdc/hardware_ini.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * Buttons on devboard - */ -#define BTNS_PORT GPIOC -// PCO -- S2 -#define BTN_S2_PIN GPIO0 -// PC1 -- S3 -#define BTN_S3_PIN GPIO1 - -/* - * LEDS: PB9 for D1, PB8 for D2 - */ -#define LEDS_PORT GPIOB -#define LED_D1_PIN GPIO9 -#define LED_D2_PIN GPIO8 - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -void check_btns(); - -#endif // __HARDWARE_INI_H__ diff --git a/simple_cdc/ld/devices.data b/simple_cdc/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/simple_cdc/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/simple_cdc/ld/stm32f103x4.ld b/simple_cdc/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/simple_cdc/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103x6.ld b/simple_cdc/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/simple_cdc/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103x8.ld b/simple_cdc/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/simple_cdc/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xB.ld b/simple_cdc/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/simple_cdc/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xC.ld b/simple_cdc/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/simple_cdc/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xD.ld b/simple_cdc/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/simple_cdc/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xE.ld b/simple_cdc/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/simple_cdc/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xF.ld b/simple_cdc/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/simple_cdc/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/ld/stm32f103xG.ld b/simple_cdc/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/simple_cdc/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/simple_cdc/main.c b/simple_cdc/main.c deleted file mode 100644 index 507dd09..0000000 --- a/simple_cdc/main.c +++ /dev/null @@ -1,88 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - //check_and_parse_UART(USART1); // also check data in UART buffers - check_btns(); - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/simple_cdc/main.h b/simple_cdc/main.h deleted file mode 100644 index 4de99af..0000000 --- a/simple_cdc/main.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/simple_cdc/sync.c b/simple_cdc/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/simple_cdc/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/simple_cdc/sync.h b/simple_cdc/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/simple_cdc/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/simple_cdc/usb_cdc_simple.bin b/simple_cdc/usb_cdc_simple.bin deleted file mode 100755 index 7d1b123..0000000 Binary files a/simple_cdc/usb_cdc_simple.bin and /dev/null differ diff --git a/simple_cdc/user_proto.c b/simple_cdc/user_proto.c deleted file mode 100644 index 3e0424c..0000000 --- a/simple_cdc/user_proto.c +++ /dev/null @@ -1,205 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("H\tshow this help\n"); - P("I\ttest entering integer value\n"); - P("T\tshow current approx. time\n"); - P("1\tswitch LED D1 state\n"); - P("2\tswitch LED D2 state\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case '1': - gpio_toggle(LEDS_PORT, LED_D1_PIN); - break; - case '2': - gpio_toggle(LEDS_PORT, LED_D2_PIN); - break; - case 'H': // show help - help(); - break; - case 'I': // enter integer & show its value - I = show_int; - READINT(); - break; - case 'T': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/simple_cdc/user_proto.h b/simple_cdc/user_proto.h deleted file mode 100644 index 69bf771..0000000 --- a/simple_cdc/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/stepper_motion/Makefile b/stepper_motion/Makefile deleted file mode 100644 index 632b018..0000000 --- a/stepper_motion/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = usb_cdc_simple -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/stepper_motion/README b/stepper_motion/README deleted file mode 100644 index 1acf5bf..0000000 --- a/stepper_motion/README +++ /dev/null @@ -1,5 +0,0 @@ -Very simple USB-CDC - -written for chinese devboard based on STM32F103RBT6 - -Press H for help \ No newline at end of file diff --git a/stepper_motion/cdcacm.c b/stepper_motion/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/stepper_motion/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/stepper_motion/cdcacm.h b/stepper_motion/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/stepper_motion/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/stepper_motion/client-p2/Makefile b/stepper_motion/client-p2/Makefile deleted file mode 100644 index da50986..0000000 --- a/stepper_motion/client-p2/Makefile +++ /dev/null @@ -1,22 +0,0 @@ -PROGRAM = p2_move -LDFLAGS = -lpthread -lcrypt -SRCS = $(wildcard *.c) -CC = gcc -DEFINES = -D_XOPEN_SOURCE=601 -CXX = gcc -CFLAGS = -Wall -Werror $(DEFINES) -OBJS = $(SRCS:.c=.o) -all : $(PROGRAM) clean -$(PROGRAM) : $(OBJS) - $(CC) $(CFLAGS) $(OBJS) $(LDFLAGS) -o $(PROGRAM) - -# some addition dependencies -# %.o: %.c -# $(CC) $(LDFLAGS) $(CFLAGS) $< -o $@ -#$(SRCS) : %.c : %.h $(INDEPENDENT_HEADERS) -# @touch $@ - -clean: - /bin/rm -f *.o *~ -depend: - $(CXX) -MM $(CXX.SRCS) diff --git a/stepper_motion/client-p2/bta_shdata.h b/stepper_motion/client-p2/bta_shdata.h deleted file mode 100644 index e63ced8..0000000 --- a/stepper_motion/client-p2/bta_shdata.h +++ /dev/null @@ -1,1161 +0,0 @@ -#pragma once -#ifndef __BTA_SHDATA_H__ -#define __BTA_SHDATA_H__ - -#ifndef _XOPEN_SOURCE -#define _XOPEN_SOURCE 501 -#endif -/* ïÓÎÏ×ÎÙÅ ÏÐÒÅÄÅÌÅÎÉÑ É ÆÕÎËÃÉÉ ÐÏÄÄÅÒÖËÉ ÍÅÖÐÒÏÇÒÁÍÍÎÏÇÏ ÉÎÔÅÒÆÅÊÓÁ */ -/* ÷ÏÚÍÏÖÎÙÅ ×ÎÅÛÎÉÅ ÏÐÒÅÄÅÌÅÎÉÑ: */ -/* BTA_MODULE - ÐÒÉ ÉÓÐ-É × ÄÏÐ. C-ÍÏÄÕÌÑÈ (ÎÅ × ÇÌÁ×Î.ÐÒÏÇÒÁÍÍÅ) */ -/* SHM_OLD_SIZE - ÄÌÑ ÇÅÎÅÒÁÃÉÉ ÐÒÅÄÙÄÕÝÅÊ ×ÅÓÉÉ ÓÔÒÕËÔÕÒÙ âôá-ÄÁÎÎÙÈ */ -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#pragma GCC diagnostic ignored "-Wunused-function" -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wmissing-braces" -#pragma GCC diagnostic ignored "-Wsequence-point" -#pragma GCC diagnostic ignored "-Wpointer-to-int-cast" -#pragma GCC diagnostic ignored "-Wimplicit-function-declaration" - -//#define int __int32_t -#define uint __uint32_t - -struct SHM_Block { /* ÏÐÉÓÁÎÉÅ ÂÌÏËÁ ÒÁÚÄÅÌÑÅÍÏÊ ÐÁÍÑÔÉ */ - union { - char name[5]; /* ËÌÀÞ ÉÄÅÎÔÅÆÉËÁÃÉÉ ÓÅÇÍÅÎÔÁ ÐÁÍÑÔÉ */ - key_t code; - } key; - int size; /* ÒÁÚÍÅÒ ÉÓÐÏÌØÚÕÅÍÏÊ ÞÁÓÔÉ × ÂÁÊÔÁÈ */ - int maxsize; /* ÒÁÚÍÅÒ ÐÒÉ ÓÏÚÄÁÎÉÉ ("Ó ÚÁÐÁÓÏÍ" ÄÌÑ ÂÕÄÕÝÉÈ ×ÅÒÓÉÊ) */ - int mode; /* ÒÅÖÉÍ ÄÏÓÔÕÐÁ (rwxrwxrwx) */ - int atflag; /* ÒÅÖÉÍ ÐÏÄÓÏÅÄÉÎÅÎÉÑ (SHM_RDONLY ÉÌÉ 0) */ - void (*init)(); /* ÐÒÏÃÅÄÕÒÁ ÉÎÉÃÉÁÌÉÚÁÃÉÉ */ - int (*check)(); /* ÐÒÏÃÅÄÕÒÁ ÐÒÏ×ÅÒËÉ */ - void (*close)(); /* ÐÒÏÃÅÄÕÒÁ ÏÔÓÏÅÄÉÎÅÎÉÑ */ - int side; /* ÔÉÐ ÐÏÄÓÏÅÄÉÎÅÎÉÑ: ëÌÉÅÎÔ/óÅÒ×ÅÒ */ - int id; /* ÄÅÓËÒÉÐÔÏÒ ÐÏÄÓÏÅÄÉÎÅÎÉÑ */ - unsigned char *addr; /* ÁÄÒÅÓ ÐÏÄÓÏÅÄÉÎÅÎÉÑ */ -}; - -struct CMD_Queue { /* ÏÐÉÓÁÎÉÅ ÏÞÅÒÅÄÉ (ËÁÎÁÌÁ) ËÏÍÁÎÄ */ - union { - char name[5]; /* ËÌÀÞ ÉÄÅÎÔÅÆÉËÁÃÉÉ ÏÞÅÒÅÄÉ */ - key_t code; - } key; - int mode; /* ÒÅÖÉÍ ÄÏÓÔÕÐÁ (rwxrwxrwx) */ - int side; /* ÔÉÐ ÐÏÄÓÏÅÄÉÎÅÎÉÑ: ëÌÉÅÎÔ/óÅÒ×ÅÒ (Sender/Receiver)*/ - int id; /* ÄÅÓËÒÉÐÔÏÒ ÐÏÄÓÏÅÄÉÎÅÎÉÑ */ - uint acckey; /* ËÌÀÞ ÄÏÓÔÕÐÁ (ÄÌÑ ÐÅÒÅÄÁÞÉ ëÌÉÅÎÔ->óÅÒ×ÅÒ) */ -}; - -#ifndef BTA_MODULE -/* ËÁÎÁÌ ËÏÍÁÎÄ ÇÌÁ×ÎÏÇÏ ÏÐÅÒÁÔÏÒÓËÏÇÏ ÉÎÔÅÒÆÅÊÓÁ (Level5)*/ -struct CMD_Queue mcmd = {{'M','c','m','d',0},0200,0,-1,0}; -/* ËÁÎÁÌ ÐÅÒÅÄÁÞÉ ÏÐÅÒÁÔÏÒÓËÉÈ (ÐÒÉ×ÅÌÅÇÉÒÏ×ÁÎÎÙÈ) ËÏÍÁÎÄ (Level4)*/ -struct CMD_Queue ocmd = {{'O','c','m','d',0},0200,0,-1,0}; -/* ËÁÎÁÌ ÐÅÒÅÄÁÞÉ ÐÏÌØÚÏ×ÁÔÅÌØÓËÉÈ (ÎÅÐÒÉ×ÅÌÅÇÉÒÏ×ÁÎÎÙÈ) ËÏÍÁÎÄ (Level2/3)*/ -struct CMD_Queue ucmd = {{'U','c','m','d',0},0200,0,-1,0}; -#else -extern struct CMD_Queue mcmd; -extern struct CMD_Queue ocmd; -extern struct CMD_Queue ucmd; -#endif - -static void send_cmd_noarg(int); -static void send_cmd_str(int, char *); -static void send_cmd_i1(int, int); -static void send_cmd_i2(int, int, int); -static void send_cmd_i3(int, int, int, int); -static void send_cmd_i4(int, int, int, int, int); -static void send_cmd_d1(int, double); -static void send_cmd_d2(int, double, double); -static void send_cmd_i1d1(int, int, double); -static void send_cmd_i2d1(int, int, int, double); -static void send_cmd_i3d1(int, int, int, int, double); - -/* ÓÐÉÓÏË ËÏÍÁÎÄ */ -/* ÉÍÑ ËÏÄ ÁÒÇÕÍÅÎÔÙ ÔÉÐ */ -#define StopTel 1 /* ÏÓÔÁÎÏ× ÔÅÌÅÓËÏÐÁ */ -#define StopTeleskope() send_cmd_noarg( 1 ) /* ÏÐÅÒ. */ -#define StartHS 2 /* ÓÔÁÒÔ ÐÒÉ×ÏÄÁ ÎÁ×ÅÄÅÎÉÑ */ -#define StartHightSpeed() send_cmd_noarg( 2 ) /* ÏÐÅÒ/ÔÓÔ*/ -#define StartLS 3 /* ÓÔÁÒÔ ÐÒÉ×ÏÄÁ ×ÅÄÅÎÉÑ */ -#define StartLowSpeed() send_cmd_noarg( 3 ) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetTmr 4 /* ÕÓÔ. Ch7_15 ÉÌÉ SysTimer */ -#define SetTimerMode(T) send_cmd_i1 ( 4, (int)(T)) /* í.ÏÐÅÒ. */ -#define SetModMod 5 /* ÕÓÔ. ÒÅÖÉÍ ÍÏÄÅÌÉÒÏ×ÁÎÉÑ */ -#define SetModelMode(M) send_cmd_i1 ( 5, (int)(M)) /* í.ÏÐÅÒ. */ -#define SetCodA 6 /* ËÏÄ ÓËÏÒÏÓÔÉ ÐÏ A */ -#define SetPKN_A(iA,sA) send_cmd_i2 ( 6, (int)(iA),(int)(sA)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetCodZ 7 /* ËÏÄ ÓËÏÒÏÓÔÉ ÐÏ Z */ -#define SetPKN_Z(iZ) send_cmd_i1 ( 7, (int)(iZ)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetCodP 8 /* ËÏÄ ÓËÏÒÏÓÔÉ ÐÏ P */ -#define SetPKN_P(iP) send_cmd_i1 ( 8, (int)(iP)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetVA 9 /* ÕÓÔ. ÓËÏÒÏÓÔØ ÐÏ A */ -#define SetSpeedA(vA) send_cmd_d1 ( 9, (double)(vA)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetVZ 10 /* ÕÓÔ. ÓËÏÒÏÓÔØ ÐÏ Z */ -#define SetSpeedZ(vZ) send_cmd_d1 (10, (double)(vZ)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetVP 11 /* ÕÓÔ. ÓËÏÒÏÓÔØ ÐÏ P */ -#define SetSpeedP(vP) send_cmd_d1 (11, (double)(vP)) /* ÏÐÅÒ/ÔÓÔ*/ -#define SetAD 12 /* ÚÁÐ.ÎÏ×ÙÅ ËÏÏÒÄÉÎÁÔÙ R.A.É Decl */ -#define SetRADec(Alp,Del) send_cmd_d2 (12, (double)(Alp),(double)(Del))/* ÐÏÌØÚ.*/ -#define SetAZ 13 /* ÚÁÐ.ËÏÏÒÄÉÎÁÔÙ ÁÚÉÍÕÔ É ÚÅÎ.ÒÁÓÓÔ.*/ -#define SetAzimZ(A,Z) send_cmd_d2 (13, (double)(A),(double)(Z))/* ÐÏÌØÚ.*/ -#define GoToAD 14 /* ÓÔÁÒÔ ÎÁ×ÅÄÅÎÉÑ ÎÁ ÏÂßÅËÔ (ÐÏ R.A.É Decl)*/ -#define GoToObject() send_cmd_noarg(14 ) /* ÏÐÅÒ. */ -#define MoveToAD 15 /* ÐÅÒÅÅÚÄ ÎÁ ÏÂßÅËÔ (ÐÏ R.A.É Decl)*/ -#define MoveToObject() send_cmd_noarg(15 ) /* ÐÏÌØÚ.*/ -#define GoToAZ 16 /* ÎÁ×ÅÄÅÎÉÅ ÐÏ ÐÏÌÏÖÅÎÉÀ (ÐÏ A Z)*/ -#define GoToAzimZ() send_cmd_noarg(16 ) /* ÏÐÅÒ. */ -#define WriteAZ 17 /* ÕÓÔÁÎÏ×ËÁ A É Z ÄÌÑ FullModel*/ -#define WriteModelAZ() send_cmd_noarg(17 ) /* ÏÐÅÒ. */ -#define SetModP 18 /* ÕÓÔ. ÒÅÖÉÍ ÉÓÐÏÌØÚÏ×ÁÎÉÑ P2 */ -#define SetPMode(pmod) send_cmd_i1 (18, (int)(pmod)) /* ÐÏÌØÚ.*/ -#define P2Move 19 /* ×ËÌ./×ÙËÌ. (+-1,0) Ä×ÉÖÅÎÉÅ P2 */ -#define MoveP2(dir) send_cmd_i1 (19, (int)(dir)) /* ÐÏÌØÚ.*/ -#define FocMove 20 /* ×ËÌ./×ÙËÌ. (+-2,+-1,0) Ä×ÉÖÅÎÉÅ ÆÏËÕÓÁ */ -#define MoveFocus(speed,time) send_cmd_i1d1(20,(int)(speed),(double)(time)) /* ÐÏÌØÚ.*/ -#define UsePCorr 21 /* ÒÅÖÉÍ ÕÞÅÔÁ ÐÏÐÒÁ×ÏË ÐÏÌÏÖÅÎÉÑ (óëî) */ -#define SwitchPosCorr(pc_flag) send_cmd_i1 (21, (int)(pc_flag)) /* ÏÐÅÒ. */ -#define SetTrkFlags 22 /* ÕÓÔ. ÆÌÁÇÏ× ÒÅÖÉÍÁ ÓÌÅÖÅÎÉÑ */ -#define SetTrkOkMode(trk_flags) send_cmd_i1 (22, (int)(trk_flags)) /* ÏÐÅÒ.*/ -#define SetTFoc 23 /* ÕÓÔ.ÆÏËÕÓÁ: 0-ðæ, 1-î1, 2-î2 */ -#define SetTelFocus(N) send_cmd_i1 ( 23, (int)(N)) /* ÏÐÅÒ. */ -#define SetVAD 24 /* ÕÓÔ.ÓË.ÓÏÂÓ×.Ä×-Ñ ÏÂßÅËÔÁ ÐÏ R.A.É Decl */ -#define SetVelAD(VAlp,VDel) send_cmd_d2 (24, (double)(VAlp),(double)(VDel))/* ÏÐÅÒ.*/ -#define SetRevA 25 /* ÕÓÔ. ÒÅÖÉÍ "ÏÂÈÏÄÁ" ÁÚÉÍÕÔÁ */ -#define SetAzRevers(amod) send_cmd_i1 (25, (int)(amod)) /* ÐÏÌØÚ.*/ -#define SetVP2 26 /* ÕÓÔ.ÓËÏÒ..Ä×-Ñ P2 (ÄÌÑ äâõ) */ -#define SetVelP2(vP2) send_cmd_d1 (26, (double)(vP2)) /* ÐÏÌØÚ.*/ -#define SetTarg 27 /* ÕÓÔ. ÃÅÌÉ ÎÁ×ÅÄÅÎÉÑ */ -#define SetSysTarg(Targ) send_cmd_i1 (27, (int)(Targ)) /* ÏÐÅÒ.*/ -#define SendMsg 28 /* ÒÁÚÍÅÝÅÎÉÅ ÓÏÏÂÝÅÎÉÑ (×ÓÅÍ ËÌÉÅÎÔÁÍ É × ÐÒÏÔÏËÏÌ) */ -#define SendMessage(Mesg) send_cmd_str (28, (char *)(Mesg)) /* ÐÏÌØÚ.*/ -#define CorrAD 29 /* ËÏÒÒÅËÃÉÑ ËÏÏÒÄÉÎÁÔ R.A.É Decl */ -#define DoADcorr(dAlp,dDel) send_cmd_d2 (29, (double)(dAlp),(double)(dDel))/* ÐÏÌØÚ.*/ -#define CorrAZ 30 /* ËÏÒÒÅËÃÉÑ ËÏÏÒÄÉÎÁÔ A É Z*/ -#define DoAZcorr(dA,dZ) send_cmd_d2 (30, (double)(dA),(double)(dZ))/* ÐÏÌØÚ.*/ -#define SetVCAZ 31 /* ÕÓÔ.ÓËÏÒ.ËÏÒÒÅËÃÉÉ ÐÏ A É Z*/ -#define SetVCorr(vA,vZ) send_cmd_d2 (31, (double)(vA),(double)(vZ))/* ÐÏÌØÚ.*/ -#define P2MoveTo 32 /* ÐÅÒÅÅÚÄ P2 ÐÏ ×ÒÅÍÅÎÉ */ -#define MoveP2To(vP2,time) send_cmd_d2 (32, (double)(vP2),(double)(time))/* ÐÏÌØÚ.*/ -#define GoToTD 33 /* ÓÔÁÒÔ ÎÁ×ÅÄÅÎÉÑ ÎÁ ÓÔÁÃÉÏÎÁÒ (ÐÏ t É Decl)*/ -#define GoToSat() send_cmd_noarg (33 ) /* ÏÐÅÒ..*/ -#define MoveToTD 34 /* ÐÅÒÅÅÚÄ ÎÁ ÓÔÁÃÉÏÎÁÒ (ÐÏ t É Decl)*/ -#define MoveToSat() send_cmd_noarg (34 ) /* ÐÏÌØÚ.*/ -#define NullCom 35 /* ÐÕÓÔÁÑ ËÏÍÁÎÄÁ (ÄÌÑ ÓÉÎÈÒÏÎÉÚÁÃÉÊ?) */ -#define SyncCom() send_cmd_noarg (35 ) /* ÏÐÅÒ. */ -#define StartTel 36 /* ËÎÏÐËÁ "ðÕÓË" ÔÅÌÅÓËÏÐÁ */ -#define StartTeleskope() send_cmd_noarg(36 ) /* ÏÐÅÒ. */ -#define SetTMod 37 /* ÕÓÔ. ÒÅÖÉÍÙ ÒÁÂÏÔÙ ÔÅÌÅÓËÏÐÁ */ -#define SetTelMode(M) send_cmd_i1 ( 37, (int)(M)) /* í.ÏÐÅÒ. */ -#define TelOn 38 /* ËÎÏÐËÁ ÷ËÌ. íÁÓÌÏ, üíõ É Ô.Ä.*/ -#define TeleskopeOn() send_cmd_noarg(38 ) /* í.ÏÐÅÒ. */ -#define SetModD 39 /* ÕÓÔ. ÒÅÖÉÍ ÉÓÐÏÌØÚÏ×ÁÎÉÑ ËÕÐÏÌÁ */ -#define SetDomeMode(dmod) send_cmd_i1 (39, (int)(dmod)) /* í.ÏÐÅÒ.*/ -#define DomeMove 40 /* ×ËÌ./×ÙËÌ. (+-1+-2,+-3,0) Ä×ÉÖÅÎÉÅ ËÕÐÏÌÁ */ -#define MoveDome(speed,time) send_cmd_i1d1(40,(int)(speed),(double)(time)) /* ÏÐÅÒ.*/ -#define SetPass 41 /* ÕÓÔ. ÐÁÒÏÌØ ÕÒÏ×ÎÑ ÄÏÓÔÕÐÁ */ -#define SetPasswd(LPass) send_cmd_str (41, (char *)(LPass)) /* í.ÏÐÅÒ.*/ -#define SetLevC 42 /* ÕÓÔ. ËÏÄ ÕÒÏ×ÎÑ ÄÏÓÔÕÐÁ */ -#define SetLevCode(Nlev,Cod) send_cmd_i2(42, (int)(Nlev),(int)(Cod)) /* í.ÏÐÅÒ.*/ -#define SetLevK 43 /* ÕÓÔ. ËÌÀÞ ÕÒÏ×ÎÑ ÄÏÓÔÕÐÁ */ -#define SetLevKey(Nlev,Key) send_cmd_i2(43, (int)(Nlev),(int)(Key)) /* í.ÏÐÅÒ.*/ -#define SetNet 44 /* ÕÓÔ. ÍÁÓËÕ É ÁÄÒÅÓ ÐÏÄÓÅÔÉ */ -#define SetNetAcc(Mask,Addr) send_cmd_i2(44, (int)(Mask),(int)(Addr)) /* í.ÏÐÅÒ.*/ -#define SetMet 45 /* ××ÏÄ ÍÅÔÅÏ ÄÁÎÎÙÈ */ -#define SetMeteo(m_id,m_val) send_cmd_i1d1(45,(int)(m_id),(double)(m_val)) /* ÏÐÅÒ.*/ -#define TurnMetOff 46 /* ÏÔÍÅÎÁ ÉÓÐ. ÍÅÔÅÏ ÄÁÎÎÙÈ */ -#define TurnMeteoOff(m_id) send_cmd_i1 (46, (int)(m_id)) /* ÏÐÅÒ.*/ -#define SetDUT1 47 /* ÕÓÔ.ÐÏÐÒ.×ÒÅÍÅÎÉ(IERS DUT1=UT1-UTC) */ -#define SetDtime(dT) send_cmd_d1 (47, (double)(dT)) /* í.ÏÐÅÒ.*/ -#define SetPM 48 /* ÕÓÔ.ÐÏÌÏÖ.ÐÏÌÀÓÁ(IERS polar motion)*/ -#define SetPolMot(Xp,Yp) send_cmd_d2 (48, (double)(Xp),(double)(Yp)) /* í.ÏÐÅÒ.*/ -#define GetSEW 49 /* ÐÒÏÞÉÔÁÔØ SEW ÐÁÒÁÍÅÔÒ */ -#define GetSEWparam(Ndrv,Indx,Cnt) send_cmd_i3(49,(int)(Ndrv),(int)(Indx),(int)(Cnt)) /* M.ÏÐÅÒ.*/ -#define PutSEW 50 /* ÚÁÐÉÓÁÔØ SEW ÐÁÒÁÍÅÔÒ */ -#define PutSEWparam(Ndrv,Indx,Key,Val) send_cmd_i4(50,(int)(Ndrv),(int)(Indx),(int)(Key),(int)(Val)) /* M.ÏÐÅÒ.*/ -#define SetLocks 51 /* ÕÓÔÁÎÏ×ËÁ ÂÌÏËÉÒÏ×ÏË ÕÐÒÁ×ÌÅÎÉÑ ÕÚÌÁÍÉ */ -#define SetLockFlags(f) send_cmd_i1 (SetLocks, (int)(f)) /* M.ÏÐÅÒ.*/ -#define ClearLocks 52 /* ÏÔÍÅÎÁ ÂÌÏËÉÒÏ×ÏË ÕÐÒÁ×ÌÅÎÉÑ ÕÚÌÁÍÉ */ -#define ClearLockFlags(f) send_cmd_i1 (ClearLocks, (int)(f)) /* M.ÏÐÅÒ.*/ -#define SetRKbits 53 /* õÓÔÁÎÏ×ËÁ ÄÏÐ.ÂÉÔÏ× PEP-RK */ -#define AddRKbits(f) send_cmd_i1 (SetRKbits, (int)(f)) /* M.ÏÐÅÒ.*/ -#define ClrRKbits 54 /* ïÞÉÓÔËÁ ÄÏÐ.ÂÉÔÏ× PEP-RK */ -#define ClearRKbits(f) send_cmd_i1 (ClrRKbits, (int)(f)) /* M.ÏÐÅÒ.*/ -#define SetSEWnd 55 /* ÕÓÔ.ÎÏÍÅÒ SEW-Ä×ÉÖËÁ ËÕÐÏÌÁ (ÄÌÑ ÉÎÄÉËÁÃÉÉ)*/ -#define SetDomeDrive(ND) send_cmd_i1 (SetSEWnd, (int)(ND)) /* í.ÏÐÅÒ.*/ -#define SEWsDome 56 /* ÷ËÌ./÷ÙËÌ. SEW-Ä×ÉÖËÏ× ËÕÐÏÌÁ */ -#define DomeSEW(OnOff) send_cmd_i1 (SEWsDome, (int)(OnOff)) /* í.ÏÐÅÒ.*/ - - -/* ÓÔÒÕËÔÕÒÁ ÄÁÎÎÙÈ ÁÌÇÏÒÉÔÍÁ ÕÐÒÁ×ÌÅÎÉÑ (ÒÁÓÐÒÅÄÅÌÅÎÉÅ "ÇÌÏÂÁÌØÎÏÊ ÏÂÌÁÓÔÉ") */ -#define BTA_Data_Ver 2 -#pragma pack(4) -//struct __attribute__((packed)) BTA_Data { -struct BTA_Data { - int magic; /* ËÏÄ ÏÐÏÚÎÁÎÉÑ ÓÔÒÕËÔÕÒÙ */ - int version; /* ÎÏÍÅÒ ×ÅÒÓÉÉ ÓÔÒÕËÔÕÒÙ = BTA_Data_Ver*/ - int size; /* ÒÁÚÍÅÒ ÓÔÒÕËÔÕÒÙ = sizeof(struct BTA_Data)*/ - int pid; -#define ServPID (sdt->pid) /*ÎÏÍÅÒ ÐÒÏÃÅÓÓÁ ÇÌ.ÕÐÒ.ÐÒÏÇÒÁÍÍÙ */ - - /* ÒÅÖÉÍÙ ÒÁÂÏÔÙ */ - int model; -#define UseModel (sdt->model) /* ×ÁÒÉÁÎÔ ÉÓÐÏÌØÚÏ×ÁÎÉÑ ÍÏÄÅÌÉÒÏ×ÁÎÉÑ */ -#define NoModel 0 /* ÏÔËÌÀÞÅÎÏ */ -#define CheckModel 1 /* ÐÒÉ×ÏÄÁ ËÏÎÔÒÏÌÉÒÕÀÔÓÑ ÐÏ ÍÏÄÅÌÉ */ -#define DriveModel 2 /* ÍÏÄÅÌÉÒÏ×ÁÎÉÅ ÐÒÉ×ÏÄÏ× É "ÓÌÅÐÏÅ" ÕÐÒÁ×ÌÅÎÉÅ ÂÅÚ ÒÅÁÌØÎÙÈ ÄÁÔÞÉËÏ× */ -#define FullModel 3 /* ÐÏÌÎÏÅ ÍÏÄÅÌÉÒÏ×ÁÎÉÅ ÂÅÚ ÔÅÌÅÓËÏÐÁ */ - int timer; -#define ClockType (sdt->timer) /* ËÁËÉÅ ÞÁÓÙ ÉÓÐÏÌØÚÕÀÔÓÑ */ -#define Ch7_15 0 /* ÷ÎÕÔÒ.ÞÁÓÙ ÕÐÒ.ÐÒÏÇÒÁÍÍÙ Ó ÓÉÎÈÒÏÎÉÚÁÃÉÅÊ ÐÏ þ7-15 */ -#define SysTimer 1 /* ôÁÊÍÅÒ ÓÉÓÔÅÍÙ (ÎÅÉÚ×ÅÓÔÎÏ ÓÉÎÈÒÏÎÉÚÉÒÏ×ÁÎÎÙÊ ÉÌÉ ÎÅÔ) */ -#define ExtSynchro 2 /* òÁÂÏÔÁÅÔ ÓÉÎÈÒÏÎÉÚÁÃÉÑ ÔÁÊÍÅÒÁ ÓÉÓÔÅÍÙ ×ÎÅÛÎÅÊ ÐÒÏÇÒÁÍÍÏÊ (bta_time ÉÌÉ xntpd)*/ - int system; -#define Sys_Mode (sdt->system) /* ÒÅÖÉÍ ÒÁÂÏÔÙ ÓÉÓÔÅÍÙ */ -#define SysStop 0 /* ïÓÔÁÎÏ× */ -#define SysWait 1 /* ïÖÉÄÁÎÉÅ ÓÔÁÒÔÁ (ÎÁ×ÅÄÅÎÉÑ) */ -#define SysPointAZ 2 /* îÁ×ÅÄÅÎÉÅ ÐÏ ÐÏÌÏÖÅÎÉÀ (ÐÏ A Z)*/ -#define SysPointAD 3 /* îÁ×ÅÄÅÎÉÅ ÎÁ ÏÂßÅËÔ (ÐÏ R.A.É Decl)*/ -#define SysTrkStop 4 /* ÷ÅÄÅÎÉÅ: ÏÖÉÄÁÎÉÅ ÓÔÁÒÔÁ */ -#define SysTrkStart 5 /* ÷ÅÄÅÎÉÅ: ÒÁÚÇÏÎ ÄÏ ÎÏÍÉÎ.ÓËÏÒÏÓÔÉ (ÏÂßÅËÔÁ)*/ -#define SysTrkMove 6 /* ÷ÅÄÅÎÉÅ: ÐÅÒÅÅÚÄ ÎÁ ÏÂßÅËÔ */ -#define SysTrkSeek 7 /* ÷ÅÄÅÎÉÅ: ÓÌÅÖÅÎÉÅ ÚÁ ÏÂßÅËÔÏÍ */ -#define SysTrkOk 8 /* ÷ÅÄÅÎÉÅ: ÒÁÓÓÏÇÌÁÓÏ×ÁÎÉÑ × ÄÏÐÕÓËÅ */ -#define SysTrkCorr 9 /* ÷ÅÄÅÎÉÅ: ËÏÒÒÅËÃÉÑ ÐÏÌÏÖÅÎÉÑ */ -#define SysTest 10 /* ôÅÓÔÉÒÏ×ÁÎÉÅ */ - int sys_target; -#define Sys_Target (sdt->sys_target) /* ÃÅÌØ ÎÁ×ÅÄÅÎÉÑ */ -#define TagPosition 0 /* ðÏÌÏÖÅÎÉÅ A/Z */ -#define TagObject 1 /* ïÂßÅËÔ Alpha/Delta */ -#define TagNest 2 /* ðÏÌÏÖÅÎÉÅ "çÎÅÚÄÏ" */ -#define TagZenith 3 /* ðÏÌÏÖÅÎÉÅ "úÅÎÉÔ" */ -#define TagHorizon 4 /* ðÏÌÏÖÅÎÉÅ "çÏÒÉÚÏÎÔ" */ -#define TagStatObj 5 /* "óÔÁÃÉÏÎÁÒ" t/Delta */ - - int tel_focus; -#define Tel_Focus (sdt->tel_focus) /* ÔÉÐ ÆÏËÕÓÁ ÔÅÌÅÓËÏÐÁ: 0-ðæ, 1-î1, 2-î2 */ -#define Prime 0 -#define Nasmyth1 1 -#define Nasmyth2 2 - double pc_coeff[8]; -#define PosCor_Coeff (sdt->pc_coeff) /* ËÏÜÆ-ÔÙ óëî ÄÌÑ ÔÅË.ÆÏËÕÓÁ */ - - /* ÓÏÓÔÏÑÎÉÅ ÔÅÌÅÓËÏÐÁ */ -#define Stopping 0 /* ïÓÔÁÎÏ× */ -#define Pointing 1 /* îÁ×ÅÄÅÎÉÅ */ -#define Tracking 2 /* ÷ÅÄÅÎÉÅ */ - int tel_state; -#define Tel_State (sdt->tel_state) /* ÒÅÁÌØÎÏ ÏÔÒÁÂÁÔÙ×ÁÅÍÏÅ */ - int req_state; -#define Req_State (sdt->req_state) /* ÚÁÔÒÅÂÏ×ÁÎÎÏÅ ÐÒÏÇÒÁÍÍÏÊ */ - int tel_hard_state; -#define Tel_Hardware (sdt->tel_hard_state) /* ÓÏÓÔÏÑÎÉÅ õóï */ -#define Hard_Off 0 /* ÐÉÔÁÎÉÅ ×ÙËÌÀÞÅÎÏ */ -#define Hard_On 1 /* ×ËÌÀÞÅÎÏ */ - - /* ÒÅÖÉÍÙ ÒÁÂÏÔÙ ÔÅÌÅÓËÏÐÁ */ - int tel_mode; -#define Tel_Mode (sdt->tel_mode) -#define Automatic 0 /* "á×ÔÏÍÁÔ" - ÎÏÒÍÁÌØÎÙÊ ÒÅÖÉÍ*/ -#define Manual 1 /* "ð/Á×Ô.ÕÐÒ." - ÐÕÌØÔÏ×ÏÊ ÒÅÖÉÍ É × ÎÅÍ:*/ -#define ZenHor 2 /* "úÅÎÉÔ-çÏÒÉÚÏÎÔ" - ÒÁÂÏÔÁ ÐÒÉ Z<5 É Z>80*/ -#define A_Move 4 /* ÒÕÞÎÏÅ Ä×ÉÖÅÎÉÅ A */ -#define Z_Move 8 /* --- "" --- Z */ -#define Balance 0x10 /* ÂÁÌÁÎÓÉÒÏ×ËÁ ÔÒÕÂÙ */ - - /* ×ËÌ./×ÙËÌ. ÒÅÖÉÍ "ÏÂÈÏÄÁ" ÁÚÉÍÕÔÁ */ - int az_mode; -#define Az_Mode (sdt->az_mode) -#define Rev_Off 0 /* ÎÏÒÍÁÌØÎÏÅ ÎÁ×ÅÄÅÎÉÅ ÎÁ ÂÌÉÖÁÊÛÅÅ ÐÏÌÏÖÅÎÉÅ ÐÏ ÁÚÉÍÕÔÕ */ -#define Rev_On 1 /* ÎÁ×ÅÄÅÎÉÅ Ó ÐÅÒÅÇÏÎÏÍ ÎÁ 360ÇÒÁÄ. */ - - /* ÒÁÂÏÔÁ P2 */ - int p2_state; -#define P2_State (sdt->p2_state) /* ÒÅÁÌØÎÏÅ ÓÏÓÔÏÑÎÉÅ ÐÒÉ×ÏÄÁ P2 */ -#define P2_Off 0 /* óÔÏÉÔ */ -#define P2_On 1 /* ÷ÅÄÅÔ */ -#define P2_Plus 2 /* ÂÙÓÔÒÏ ÅÄÅÔ × + */ -#define P2_Minus -2 /* ÂÙÓÔÒÏ ÅÄÅÔ × - */ - int p2_req_mode; -#define P2_Mode (sdt->p2_req_mode) /* ÒÅÖÉÍ ÉÓÐÏÌØÚÏ×ÁÎÉÑ P2 (ÐÏËÁ: ÷ËÌ/÷ÙËÌ)*/ - - /* ÓÏÓÔÏÑÎÉÅ ÐÒÉ×ÏÄÁ ÆÏËÕÓÁ */ - int focus_state; -#define Foc_State (sdt->focus_state) -#define Foc_Off 0 /* óÔÏÉÔ */ -#define Foc_Lplus 1 /* ÍÅÄÌ. ÅÄÅÔ × + */ -#define Foc_Lminus -1 /* ÍÅÄÌ. ÅÄÅÔ × - */ -#define Foc_Hplus 2 /* ÂÙÓÔÒÏ ÅÄÅÔ × + */ -#define Foc_Hminus -2 /* ÂÙÓÔÒÏ ÅÄÅÔ × - */ - - /* ÓÏÓÔÏÑÎÉÅ ÐÒÉ×ÏÄÁ ËÕÐÏÌÁ */ - int dome_state; -#define Dome_State (sdt->dome_state) -#define D_On 7 /* á×ÔÏÍÁÔÉÞÅÓËÏÅ ÓÏÇÌÁÓÏ×ÁÎÉÅ Ó ÔÅÌÅÓËÏÐÏÍ */ -#define D_Off 0 /* óÔÏÉÔ */ -#define D_Lplus 1 /* ÍÅÄÌ. ÅÄÅÔ × + */ -#define D_Lminus -1 /* ÍÅÄÌ. ÅÄÅÔ × - */ -#define D_Mplus 2 /* ÓÒÅÄ.ÓËÏÒ. × + */ -#define D_Mminus -2 /* ÓÒÅÄ.ÓËÏÒ. × - */ -#define D_Hplus 3 /* ÂÙÓÔÒÏ ÅÄÅÔ × + */ -#define D_Hminus -3 /* ÂÙÓÔÒÏ ÅÄÅÔ × - */ - -/* ÕÞÅÔ ÐÏÐÒÁ×ÏË ÐÏÌÏÖÅÎÉÑ (óëî) */ - int pcor_mode; -#define Pos_Corr (sdt->pcor_mode) /* ËÏÒÒÅËÃÉÑ ÐÏÌÏÖÅÎÉÑ ÏÂßÅËÔÁ ÐÏ A/Z: ÷ËÌ/÷ÙËÌ*/ -#define PC_Off 0 /* ÷ÙËÌ. */ -#define PC_On 1 /* ÷ËÌ. */ - -/* ÆÌÁÇÉ ×ËÌ/×ÙËÌ. ×ÁÒÉÁÎÔÏ× ÒÅÖÉÍÁ ÓÌÅÖÅÎÉÑ */ - int trkok_mode; -#define TrkOk_Mode (sdt->trkok_mode) -#define UseDiffVel 1 /* ÏÐÒÅÄÅÌÅÎÉÅ&ÕÞÅÔ ÐÏÐÒÁ×ÏË ÒÅÁÌØÎÏÊ ÓËÏÒÏÓÔÉ ÐÒÉ×ÏÄÏ× (~ÉÚÏÄÏÒÏÍ)*/ -#define UseDiffAZ 2 /* ÓÌÅÖÅÎÉÅ ÐÏ ÒÁÓÓÏÇÌÁÓÏ×ÁÎÉÀ (ÉÎÁÞÅ ÕÓÔ.ÒÁÓÓÞÅÔÎ.ÓËÏÒÏÓÔÅÊ) */ -#define UseDFlt 4 /* ×ËÌ. ÃÉÆÒÏ×ÏÇÏ ÆÉÌØÔÒÁ ÒÁÓÓÏÇÌÁÓÏ×ÁÎÉÊ */ - - /* ××ÅÄÅÎÎÙÅ ÚÎÁÞÅÎÉÑ */ - double i_alpha, i_delta; -#define InpAlpha (sdt->i_alpha) /* ××ÅÄÅÎÎÁÑ ËÏÏÒÄÉÎÁÔÁ R.A. (sec) */ -#define InpDelta (sdt->i_delta) /* -- " -- Decl. (") */ - double s_alpha, s_delta; -#define SrcAlpha (sdt->s_alpha) /* ÉÓÈÏÄÎÁÑ ËÏÏÒÄÉÎÁÔÁ R.A. (sec) */ -#define SrcDelta (sdt->s_delta) /* -- " -- Decl. (") */ - double v_alpha, v_delta; -#define VelAlpha (sdt->v_alpha) /* ÓË.ÓÏÂÓ×.Ä×-Ñ ÏÂßÅËÔÁ ÐÏ R.A. (sec/ÓÅË) */ -#define VelDelta (sdt->v_delta) /* -- " -- Decl. ("/ÓÅË) */ - double i_azim, i_zdist; -#define InpAzim (sdt->i_azim) /* ÄÌÑ ÎÁ×ÅÄÅÎÉÑ ÐÏ ÁÚÉÍÕÔÕ (") */ -#define InpZdist (sdt->i_zdist) /* -- " -- ÚÅÎ.ÒÁÓÓÔ. (") */ - - /* ÒÁÓÓÞÅÔÎÙÅ ÚÎÁÞÅÎÉÑ */ - double c_alpha, c_delta; -#define CurAlpha (sdt->c_alpha) /* ÔÅËÕÝÁÑ ËÏÏÒÄÉÎÁÔÁ R.A. (sec) */ -#define CurDelta (sdt->c_delta) /* -- " -- Decl. (") */ - double tag_a, tag_z, tag_p; -#define tag_A (sdt->tag_a) /* ÔÅËÕÝÉÊ A (") ÏÂßÅËÔÁ */ -#define tag_Z (sdt->tag_z) /* - " - Z (") - " - */ -#define tag_P (sdt->tag_p) /* - " - P (") - " - */ - double pcor_a, pcor_z, refr_z; -#define pos_cor_A (sdt->pcor_a) /* ÐÏÐÒÁ×ËÁ ÐÏÌÏÖÅÎÉÑ ÏÂßÅËÔÁ ÐÏ A (") */ -#define pos_cor_Z (sdt->pcor_z) /* - " - - " - ÐÏ Z (") */ -#define refract_Z (sdt->refr_z) /* ÐÏÐÒÁ×ËÁ ÚÁ ÒÅÆÒÁËÃÉÀ ÄÌÑ ÏÂßÅËÔÁ (") */ - double tcor_a, tcor_z, tref_z; -#define tel_cor_A (sdt->tcor_a) /* ÐÏÐÒÁ×ËÁ ÏÂÒ.ÐÅÒÅÓÞÅÔÁ ÐÏÌÏÖÅÎÉÑ ÔÅÌÅÓËÏÐÁ ÐÏ A (") */ -#define tel_cor_Z (sdt->tcor_z) /* - " - - " - - " - ÐÏ Z (") */ -#define tel_ref_Z (sdt->tref_z) /* ÐÏÐÒÁ×ËÁ ÏÂÒ.ÐÅÒÅÓÞÅÔÁ ÚÁ ÒÅÆÒÁËÃÉÀ (") */ - double diff_a, diff_z, diff_p; -#define Diff_A (sdt->diff_a) /* ÒÁÓÓÏÇÌ-Å(ÏÓÔÁÌÏÓØ ÅÈÁÔØ) ÐÏ A (") */ -#define Diff_Z (sdt->diff_z) /* - " - - " - Z (") */ -#define Diff_P (sdt->diff_p) /* - " - - " - P (") */ - double vbasea,vbasez,vbasep; -#define vel_objA (sdt->vbasea) /* ÂÁÚÏ×ÁÑ ÓËÏÒÏÓÔØ ÏÂßÅËÔÁ ÐÏ A ("/ÓÅË) */ -#define vel_objZ (sdt->vbasez) /* - " - - " - Z - " - */ -#define vel_objP (sdt->vbasep) /* - " - - " - P - " - */ - double diffva,diffvz,diffvp; -#define diff_vA (sdt->diffva) /* ÐÏÐÒÁ×ËÁ ÒÅÁÌØÎÏÊ ÓËÏÒÏÓÔÉ ÐÒÉ×ÏÄÁ ÐÏ ÁÚÉÍÕÔÕ */ -#define diff_vZ (sdt->diffvz) /* -- "" -- -- "" -- ÐÏ Z */ -#define diff_vP (sdt->diffvp) /* -- "" -- -- "" -- ÐÏ P */ - double speeda,speedz,speedp; -#define speedA (sdt->speeda) /* ÓËÏÒÏÓÔØ ÐÏ A ("/ÓÅË) ÄÌÑ ÕÐÒÁ×ÌÅÎÉÑ ÐÒÉ×ÏÄÏÍ */ -#define speedZ (sdt->speedz) /* - " - Z - " - */ -#define speedP (sdt->speedp) /* - " - P - " - */ - double m_time_precip; -#define Precip_time (sdt->m_time_precip)/* ÍÏÍÅÎÔ ×ÒÅÍÅÎÉ ÐÏÑ×ÌÅÎÉÑ ÏÓÁÄËÏ× (precipitations)*/ - unsigned char reserve[16]; -#define Reserve (sdt->reserve) /* Ó×ÏÂÏÄÎÏÅ ÍÅÓÔÏ */ - double rspeeda, rspeedz, rspeedp; -#define req_speedA (sdt->rspeeda) /* ÓËÏÒÏÓÔØ ("/ÓÅË) ×ÙÄÁÎÎÁÑ ÎÁ ÐÒÉ×ÏÄ A */ -#define req_speedZ (sdt->rspeedz) /* - " - Z */ -#define req_speedP (sdt->rspeedp) /* - " - P */ - double simvela, simvelz, simvelp, simvelf, simveld; -#define mod_vel_A (sdt->simvela) /* ÓËÏÒÏÓÔØ ÐÏ A ("/ÓÅË) ÍÏÄÅÌØÎÁÑ */ -#define mod_vel_Z (sdt->simvelz) /* - " - Z - " - */ -#define mod_vel_P (sdt->simvelp) /* - " - P - " - */ -#define mod_vel_F (sdt->simvelf) /* - " - F - " - */ -#define mod_vel_D (sdt->simvelf) /* - " - D - " - */ - - - /* ÒÅÚÕÌØÔÁÔÙ ÉÚÍÅÒÅÎÉÑ ÄÁÔÞÉËÏ× É ÒÁÓÓÞÉÔÁÎÎÙÅ ÐÏ ÎÉÍ ÚÎÁÞÅÎÉÑ */ - uint kost; -#define code_KOST (sdt->kost) /* ÓÏÓÔ. ÔÅÌÅÓËÏÐÁ É ÒÕÞÎÏÊ ËÏÒÒÅËÃÉÉ */ - /* 0x8000 - ÁÚÉÍÕÔ ÐÏÌÏÖÉÔÅÌØÎÙÊ */ - /* 0x4000 - ÏÔÒÁÂÏÔËÁ ×ËÌ. */ - /* 0x2000 - ÒÅÖÉÍ ×ÅÄÅÎÉÑ */ - /* 0x1000 - ÏÔÒÁÂÏÔËÁ P2 ×ËÌ.*/ - /* 0x01F0 - ÓË.ËÏÒÒ. 0.2 0.4 1.0 2.0 5.0("/ÓÅË) */ - /* 0x000F - ÎÁÐÒ.ËÏÒÒ. +Z -Z +A -A */ - double m_time, s_time, l_time; -#define M_time (sdt->m_time) /* ÔÅËÕÝÅÅ ÍÏÓËÏ×ÓËÏÅ ×ÒÅÍÑ (ÔÅÐÅÒØ UTC!)*/ -#define S_time (sdt->s_time) /* ÔÅËÕÝÅÅ Ú×ÅÚÄÎÏÅ ×ÒÅÍÑ */ -#define L_time (sdt->l_time) /* ×ÒÅÍÑ ÒÁÂÏÔÙ ÐÒÏÇÒÁÍÍÙ */ - uint ppndd_a, ppndd_z, ppndd_p, ppndd_b; -#define ppndd_A (sdt->ppndd_a) /* ËÏÄ ÄÁÔÞÉËÁ ððîää (ÇÒÕÂÏÇÏ ÏÔÓÞÅÔÁ) A */ -#define ppndd_Z (sdt->ppndd_z) /* - "" - Z */ -#define ppndd_P (sdt->ppndd_p) /* - "" - P */ -#define ppndd_B (sdt->ppndd_b) /* ËÏÄ ÄÁÔÞÉËÁ ððîää ÄÁ×ÌÅÎÉÑ */ - uint dup_a, dup_z, dup_p, dup_f, dup_d; -#define dup_A (sdt->dup_a) /* ËÏÄ çÒÅÑ ÄÁÔÞÉËÁ äõð (ÔÏÞÎÏÇÏ ÏÔÓÞÅÔÁ) A */ -#define dup_Z (sdt->dup_z) /* - "" - Z */ -#define dup_P (sdt->dup_p) /* - "" - P */ -#define dup_F (sdt->dup_f) /* ËÏÄ çÒÅÑ ÄÁÔÞÉËÁ äõð ÆÏËÕÓÁ ÔÅÌÅÓËÏÐÁ */ -#define dup_D (sdt->dup_d) /* ËÏÄ çÒÅÑ ÄÁÔÞÉËÁ äõð ÐÏÌÏÖÅÎÉÑ ËÕÐÏÌÁ */ - uint low_a, low_z, low_p, low_f, low_d; -#define low_A (sdt->low_a) /* 14Ò-× Ä×.ËÏÄÁ ÔÏÞÎÏÇÏ ÏÔÓÞÅÔÁ A */ -#define low_Z (sdt->low_z) /* - "" - Z */ -#define low_P (sdt->low_p) /* - "" - P */ -#define low_F (sdt->low_f) /* ËÏÄ ÏÔÓÞÅÔÁ ÆÏËÕÓÁ ÔÅÌÅÓËÏÐÁ */ -#define low_D (sdt->low_d) /* ËÏÄ ÏÔÓÞÅÔÁ ÐÏÌÏÖÅÎÉÑ ËÕÐÏÌÁ */ - uint code_a, code_z, code_p, code_b, code_f, code_d; -#define code_A (sdt->code_a) /* 23Ò-× Ä×.ËÏÄÁ ÏÔÓÞÅÔÁ A */ -#define code_Z (sdt->code_z) /* - "" - Z */ -#define code_P (sdt->code_p) /* - "" - P */ -#define code_B (sdt->code_b) /* ËÏÄ ÄÁ×ÌÅÎÉÑ */ -#define code_F (sdt->code_f) /* ËÏÄ ÏÔÓÞÅÔÁ ÆÏËÕÓÁ ÔÅÌÅÓËÏÐÁ */ -#define code_D (sdt->code_d) /* ËÏÄ ÏÔÓÞÅÔÁ ÐÏÌÏÖÅÎÉÑ ËÕÐÏÌÁ */ - uint adc[8]; -#define ADC(N) (sdt->adc[(N)]) /* ËÏÄÙ 8-ÍÉ ËÁÎÁÌÏ× áãð PCL818 */ -#define code_T1 ADC(0) /* ËÏÄ ÄÁÔÞÉËÁ ÎÁÒÕÖ. ÔÅÍÐÅÒÁÔÕÒÙ*/ -#define code_T2 ADC(1) /* ËÏÄ ÄÁÔÞÉËÁ ÔÅÍÐÅÒÁÔÕÒÙ ÐÏÄ ËÕÐ.*/ -#define code_T3 ADC(2) /* ËÏÄ ÄÁÔÞÉËÁ ÔÅÍÐÅÒÁÔÕÒÙ ÚÅÒËÁÌÁ */ -#define code_Wnd ADC(3) /* ËÏÄ ÄÁÔÞÉËÁ ×ÅÔÒÁ */ - double val_a, val_z, val_p, val_b, val_f, val_d; - double val_t1, val_t2, val_t3, val_wnd; -#define val_A (sdt->val_a) /* ÏÔÓÞÅÔ A (") */ -#define val_Z (sdt->val_z) /* - " - Z (") */ -#define val_P (sdt->val_p) /* - " - P (") */ -#define val_B (sdt->val_b) /* ÄÁ×ÌÅÎÉe (ÍÍ.ÒÔ.ÓÔ.)*/ -#define val_F (sdt->val_f) /* ÆÏËÕÓ ÔÅÌÅÓËÏÐÁ (ÍÍ) */ -#define val_D (sdt->val_d) /* ÐÏÌÏÖÅÎÉÅ ËÕÐÏÌÁ (") */ -#define val_T1 (sdt->val_t1) /* ÎÁÒÕÖ. ÔÅÍÐÅÒÁÔÕÒÁ (ÇÒ.)*/ -#define val_T2 (sdt->val_t2) /* ÔÅÍÐÅÒÁÔÕÒÁ ÐÏÄ ËÕÐ.(ÇÒ.)*/ -#define val_T3 (sdt->val_t3) /* ÔÅÍÐÅÒÁÔÕÒÁ ÚÅÒËÁÌÁ (ÇÒ.)*/ -#define val_Wnd (sdt->val_wnd) /* ×ÅÔÅÒ (Í/ÓÅË)*/ - double val_alp, val_del; -#define val_Alp (sdt->val_alp) /* ÏÂÒÁÔÎÙÊ ÐÅÒÅÓÞÅÔ R.A. (sec) */ -#define val_Del (sdt->val_del) /* -- " -- Decl. (") */ - - double vel_a, vel_z, vel_p, vel_f, vel_d; -#define vel_A (sdt->vel_a) /* ÓËÏÒÏÓÔØ ÐÏ A ("/ÓÅË) ÉÚÍÅÒÅÎÎÁÑ */ -#define vel_Z (sdt->vel_z) /* - " - Z - " - */ -#define vel_P (sdt->vel_p) /* - " - P - " - */ -#define vel_F (sdt->vel_f) /* - " - F - " - */ -#define vel_D (sdt->vel_d) /* - " - D - " - */ - - /* ÏÞÅÒÅÄØ ÐÏÓÌÅÄÎÉÈ ÓÉÓÔÅÍÎÙÈ ÓÏÏÂÝÅÎÉÊ */ -#define MesgNum 3 -#define MesgLen 39 - //struct __attribute__((packed)) SysMesg { - struct SysMesg { - int seq_num; - char type; -#define MesgEmpty 0 -#define MesgInfor 1 -#define MesgWarn 2 -#define MesgFault 3 -#define MesgLog 4 - char text[MesgLen]; - } sys_msg_buf[MesgNum]; -#define Sys_Mesg(N) (sdt->sys_msg_buf[N]) - - /* ÕÐÒÁ×ÌÅÎÉÅ ÄÏÓÔÕÐÏÍ */ - /* ËÏÄÙ ÕÓÔÁÎÏ×ËÉ ÕÒÏ×ÎÅÊ ÄÏÓÔÕÐÁ ÄÌÑ ËÌÉÅÎÔÏ× */ - uint code_lev1,code_lev2,code_lev3,code_lev4,code_lev5; -#define code_Lev1 (sdt->code_lev1) /* "ÕÄÁÌÅÎÎÙÊ ÎÁÂÌÀÄÁÔÅÌØ" - ÔÏÌØËÏ ÉÎÆÏÒÍÁÃÉÑ */ -#define code_Lev2 (sdt->code_lev2) /* "ÍÅÓÔÎÙÊ ÎÁÂÌÀÄÁÔÅÌØ" - + ××ÏÄ ËÏÏÒÄÉÎÁÔ */ -#define code_Lev3 (sdt->code_lev3) /* "ÇÌÁ×ÎÙÊ ÎÁÂÌÀÄÁÔÅÌØ" - + A/Z-ËÏÒÒ-Ñ, ÕÐÒ.P2/F */ -#define code_Lev4 (sdt->code_lev4) /* "ÏÐÅÒÁÔÏÒ" - + ÐÕÓË/ÓÔÏÐ ÔÅÌÅÓË., ÔÅÓÔÉÒÏ×ÁÎÉÅ */ -#define code_Lev5 (sdt->code_lev5) /* "ÇÌÁ×ÎÙÊ ÏÐÅÒÁÔÏÒ" - ×ÓÅ ÏÐÅÒÁÃÉÉ */ - /* ÏÇÒÁÎÉÞÅÎÉÅ ÓÅÔÅ×ÏÇÏ ÄÏÓÔÕÐÁ */ - uint netmask, netaddr, acsmask, acsaddr; -#define NetMask (sdt->netmask) /* ÍÁÓËÁ ÐÏÄÓÅÔÉ (ÏÂÙÞÎÏ: 255.255.255.0) */ -#define NetWork (sdt->netaddr) /* ÁÄÒÅÓ ÐÏÄÓÅÔÉ (ÎÁÐÒÉÍÅÒ: 192.168.3.0) */ -#define ACSMask (sdt->acsmask) /* ÍÁÓËÁ áóõ-ÓÅÔÉ (ÎÁÐÒÉÍÅÒ: 255.255.255.0) */ -#define ACSNet (sdt->acsaddr) /* ÁÄÒÅÓ áóõ-ÓÅÔÉ (ÎÁÐÒÉÍÅÒ: 192.168.13.0) */ - - /* ××ÏÄ ÍÅÔÅÏ-ÄÁÎÎÙÈ */ - int meteo_stat; -#define MeteoMode (sdt->meteo_stat) /* ÆÌÁÇÉ ÄÁÔÞÉËÏ× É ××ÏÄÁ ÄÁÎÎÙÈ*/ -#define INPUT_B 1 /* ÄÁ×ÌÅÎÉÅ *//* ÆÌÁÇÉ ÒÕÞÎÏÇÏ ××ÏÄÁ ÍÅÔÅÏ ÄÁÎÎÙÈ */ -#define INPUT_T1 2 /* T-ÎÁÒÕÖÎÁÑ */ -#define INPUT_T2 4 /* T-ÐÏÄËÕÐÏÌØÎÁÑ */ -#define INPUT_T3 8 /* T-ÚÅÒËÁÌÁ */ -#define INPUT_WND 0x10 /* ×ÅÔÅÒ */ -#define INPUT_HMD 0x20 /* ×ÌÁÖÎÏÓÔØ */ -#define SENSOR_B (INPUT_B <<8) /* ÆÌÁÇÉ ×ÎÅÛÎÉÈ ÍÅÔÅÏ-ÄÁÔÞÉËÏ× (e.g.ÐÏ CAN-ÛÉÎÅ)*/ -#define SENSOR_T1 (INPUT_T1 <<8) -#define SENSOR_T2 (INPUT_T2 <<8) -#define SENSOR_T3 (INPUT_T3 <<8) -#define SENSOR_WND (INPUT_WND<<8) -#define SENSOR_HMD (INPUT_HMD<<8) -#define ADC_B (INPUT_B <<16) /* ÆÌÁÇÉ ÓÞÉÔÙ×ÁÎÉÑ Ó áãð ÕÐÒ.ËÏÍÐÕÔÅÒÁ */ -#define ADC_T1 (INPUT_T1 <<16) -#define ADC_T2 (INPUT_T2 <<16) -#define ADC_T3 (INPUT_T3 <<16) -#define ADC_WND (INPUT_WND<<16) -#define ADC_HMD (INPUT_HMD<<16) -#define NET_B (INPUT_B <<24) /* ÆÌÁÇÉ ÐÏÌÕÞÅÎÉÑ ÄÁÎÎÙÈ Ó ÍÅÔÅÏÓÔÁÎÃÉÉ ÐÏ ÓÅÔÉ */ -#define NET_T1 (INPUT_T1 <<24) -#define NET_WND (INPUT_WND<<24) -#define NET_HMD (INPUT_HMD<<24) - double inp_b, inp_t1, inp_t2, inp_t3, inp_wnd; -#define inp_B (sdt->inp_b) /* ÄÁ×ÌÅÎÉe (ÍÍ.ÒÔ.ÓÔ.)*/ -#define inp_T1 (sdt->inp_t1) /* ÎÁÒÕÖ. ÔÅÍÐÅÒÁÔÕÒÁ (ÇÒ.)*/ -#define inp_T2 (sdt->inp_t2) /* ÔÅÍÐÅÒÁÔÕÒÁ ÐÏÄ ËÕÐ.(ÇÒ.)*/ -#define inp_T3 (sdt->inp_t3) /* ÔÅÍÐÅÒÁÔÕÒÁ ÚÅÒËÁÌÁ (ÇÒ.)*/ -#define inp_Wnd (sdt->inp_wnd) /* ×ÅÔÅÒ (Í/ÓÅË)*/ - - double temper, press; -#define Temper (sdt->temper) /* ÔÅÍÒÅÒÁÔÕÒÁ ÉÓÐÏÌØÚÕÅÍÁÑ ÄÌÑ ÒÅÆÒÁËÃÉÉ */ -#define Pressure (sdt->press) /* ÄÁ×ÌÅÎÉÅ ÉÓÐÏÌØÚÕÅÍÏÅ ÄÌÑ ÒÅÆÒÁËÃÉÉ */ - double m_time10, m_time15; -#define Wnd10_time (sdt->m_time10) /* ÍÏÍÅÎÔ ×ÒÅÍÅÎÉ ÐÏÒÙ×Á >=10Í/ÓÅË*/ -#define Wnd15_time (sdt->m_time15) /* - " - - " - - " - >=15Í/ÓÅË*/ - - /* IERS DUT1 (ÉÓÔÏÞÎÉË: ftp://maia.usno.navy.mil/ser7/ser7.dat) */ - double dut1; -#define DUT1 (sdt->dut1) /* ÐÏÐÒÁ×ËÁ ÓÒ.ÓÏÌÎÅÞÎÏÇÏ ×ÒÅÍÅÎÉ: DUT1 = UT1-UTC */ - - double a_time, z_time, p_time; -#define A_time (sdt->a_time) /* ÍÏÍÅÎÔ ÓÞÉÔÙ×ÁÎÉÑ ÄÁÔÞÉËÁ A */ -#define Z_time (sdt->z_time) /* - " - - " - - " - Z */ -#define P_time (sdt->p_time) /* - " - - " - - " - P */ - - double speedain, speedzin, speedpin; -#define speedAin (sdt->speedain) /* ÐÏÓÔÏÑÎÎÁÑ ÓËÏÒÏÓÔØ ÕÓÔ-Ñ ÐÏ A */ -#define speedZin (sdt->speedzin) /* ÐÏÓÔÏÑÎÎÁÑ ÓËÏÒÏÓÔØ ÕÓÔ-Ñ ÐÏ Z */ -#define speedPin (sdt->speedpin) /* ÐÏÓÔÏÑÎÎÁÑ ÓËÏÒÏÓÔØ ÕÓÔ-Ñ ÐÏ P2*/ - - double acc_a, acc_z, acc_p, acc_f, acc_d; -#define acc_A (sdt->acc_a) /* ÕÓËÏÒÅÎÉÅ ÐÏ A ("/ÓÅË^2) */ -#define acc_Z (sdt->acc_z) /* - " - Z - " - */ -#define acc_P (sdt->acc_p) /* - " - P - " - */ -#define acc_F (sdt->acc_f) /* - " - F - " - */ -#define acc_D (sdt->acc_d) /* - " - D - " - */ - - uint code_sew; -#define code_SEW (sdt->code_sew) /* ËÏÄ ÓÐÅÃ.ÄÏÓÔÕÐÁ Ë SEW-ËÏÎÔÒÏÌÌÅÒÁÍ */ - -/* ÐÁÒÁÍÅÔÒÙ SEW-ËÏÎÔÒÏÌÌÅÒÏ× */ -//struct __attribute__((packed)) SEWdata { -struct SEWdata { - int status; - double set_speed; - double mes_speed; - double current; - int index; - union { - unsigned char b[4]; - __uint32_t l; - } value; -} sewdrv[3]; -#define statusSEW(Drv) (sdt->sewdrv[(Drv)-1].status) /*ÓÏÓÔÏÑÎÉÅ ËÏÎÔÒÏÌÌÅÒÁ*/ -#define statusSEW1 (sdt->sewdrv[0].status) -#define statusSEW2 (sdt->sewdrv[1].status) -#define statusSEW3 (sdt->sewdrv[2].status) -#define speedSEW(Drv) (sdt->sewdrv[(Drv)-1].set_speed) /*ÕÓÔÁÎÏ×ÌÅÎÎÁÑ ÓËÏÒÏÓÔØ*/ -#define speedSEW1 (sdt->sewdrv[0].set_speed) /* ÏÂ/ÍÉÎ (rpm)*/ -#define speedSEW2 (sdt->sewdrv[1].set_speed) -#define speedSEW3 (sdt->sewdrv[2].set_speed) -#define vel_SEW(Drv) (sdt->sewdrv[(Drv)-1].mes_speed) /*ÉÚÍÅÒÅÎÎÁÑ ÓËÏÒÏÓÔØ */ -#define vel_SEW1 (sdt->sewdrv[0].mes_speed) /* ÏÂ/ÍÉÎ (rpm)*/ -#define vel_SEW2 (sdt->sewdrv[1].mes_speed) -#define vel_SEW3 (sdt->sewdrv[2].mes_speed) -#define currentSEW(Drv) (sdt->sewdrv[(Drv)-1].current) /*ÔÏË (á)*/ -#define currentSEW1 (sdt->sewdrv[0].current) -#define currentSEW2 (sdt->sewdrv[1].current) -#define currentSEW3 (sdt->sewdrv[2].current) -#define indexSEW(Drv) (sdt->sewdrv[(Drv)-1].index) /*ÎÏÍÅÒ ÐÁÒÁÍÅÔÒÁ*/ -#define indexSEW1 (sdt->sewdrv[0].index) -#define indexSEW2 (sdt->sewdrv[1].index) -#define indexSEW3 (sdt->sewdrv[2].index) -#define valueSEW(Drv) (sdt->sewdrv[(Drv)-1].value.l) /*ËÏÄ ÚÎÁÞÅÎÉÑ ÐÁÒÁÍÅÔÒÁ*/ -#define valueSEW1 (sdt->sewdrv[0].value.l) -#define valueSEW2 (sdt->sewdrv[1].value.l) -#define valueSEW3 (sdt->sewdrv[2].value.l) -#define bvalSEW(Drv,Nb) (sdt->sewdrv[(Drv)-1].value.b[Nb]) /*ÂÁÊÔ ËÏÄÁ ÚÎÁÞÅÎÉÑ ÐÁÒÁÍÅÔÒÁ*/ - -/* ÉÎÆÏÒÍÁÃÉÑ ÏÔ PEP-ËÏÎÔÒÏÌÌÅÒÏ× */ - uint pep_code_a, pep_code_z, pep_code_p; -#define PEP_code_A (sdt->pep_code_a) /* 23Ò-× Ä×.ËÏÄÁ ÏÔÓÞÅÔÁ A */ -#define PEP_code_Z (sdt->pep_code_z) /* - "" - Z */ -#define PEP_code_P (sdt->pep_code_p) /* - "" - P */ - uint pep_sw_a, pep_sw_z, pep_sw_p; -#define switch_A (sdt->pep_sw_a) /* ËÏÄ ËÏÎÃÅ×ÉËÏ× ÁÚÉÍÕÔÁ */ -#define Sw_minus_A 1 /* ÁÚÉÍÕÔ ÏÔÒÉÃÁÔÅÌØÎÙÊ (ÓÍ. code_KOST&0x8000)*/ -#define Sw_plus240_A 2 /* ËÏÎÃÅ×ÉË "+240ÇÒÁÄ" */ -#define Sw_minus240_A 4 /* ËÏÎÃÅ×ÉË "-240ÇÒÁÄ" */ -#define Sw_minus45_A 8 /* ÐÏÌÏÖÅÎÉÅ "× ÇÏÒÉÚÏÎÔ" (~-46ÇÒÁÄ)*/ -#define switch_Z (sdt->pep_sw_z) /* ËÏÄ ËÏÎÃÅ×ÉËÏ× Z */ -#define Sw_0_Z 0x01 /* ËÏÎÃÅ×ÉË "0ÇÒÁÄ" */ -#define Sw_5_Z 0x02 /* ËÏÎÃÅ×ÉË "5ÇÒÁÄ" */ -#define Sw_20_Z 0x04 /* ËÏÎÃÅ×ÉË "20ÇÒÁÄ" */ -#define Sw_60_Z 0x08 /* ËÏÎÃÅ×ÉË "60ÇÒÁÄ" */ -#define Sw_80_Z 0x10 /* ËÏÎÃÅ×ÉË "80ÇÒÁÄ" */ -#define Sw_90_Z 0x20 /* ËÏÎÃÅ×ÉË "90ÇÒÁÄ" */ -#define switch_P (sdt->pep_sw_p) /* - "" - óðæ */ -#define Sw_No_P 0x00 /* "îÅÔ ËÏÎÃÅ×ÉËÏ×" */ -#define Sw_22_P 0x01 /* ËÏÎÃÅ×ÉË "22ÇÒÁÄ" */ -#define Sw_89_P 0x02 /* ËÏÎÃÅ×ÉË "89ÇÒÁÄ" */ -#define Sw_Sm_P 0x80 /* ÄÁÔÞÉË ÄÙÍÁ óðæ */ - uint pep_code_f, pep_code_d, pep_code_ri, pep_code_ro; -#define PEP_code_F (sdt->pep_code_f) /* ËÏÄ ÏÔÓÞÅÔÁ ÆÏËÕÓÁ ÔÅÌÅÓËÏÐÁ */ -#define PEP_code_D (sdt->pep_code_d) /* ËÏÄ ÏÔÓÞÅÔÁ ÐÏÌÏÖÅÎÉÑ ËÕÐÏÌÁ */ -#define PEP_code_Rin (sdt->pep_code_ri)/* ËÏÄ ÐÒÉÎÑÔÙÊ ÉÚ òë */ -#define PEP_code_Rout (sdt->pep_code_ro)/* ËÏÄ ×ÙÄÁ×ÁÅÍÙÊ × òë */ - unsigned char pep_on[10]; /* ÆÌÁÇÉ ÒÁÂÏÔÙ PEP-ËÏÎÔÒÏÌÌÅÒÏ× */ -#define PEP_A_On (sdt->pep_on[0]) -#define PEP_A_Off (PEP_A_On==0) -#define PEP_Z_On (sdt->pep_on[1]) -#define PEP_Z_Off (PEP_Z_On==0) -#define PEP_P_On (sdt->pep_on[2]) -#define PEP_P_Off (PEP_P_On==0) -#define PEP_F_On (sdt->pep_on[3]) -#define PEP_F_Off (PEP_F_On==0) -#define PEP_D_On (sdt->pep_on[4]) -#define PEP_D_Off (PEP_D_On==0) -#define PEP_R_On (sdt->pep_on[5]) -#define PEP_R_Off ((PEP_R_On&1)==0) -#define PEP_R_Inp ((PEP_R_On&2)!=0) -#define PEP_K_On (sdt->pep_on[6]) -#define PEP_K_Off ((PEP_K_On&1)==0) -#define PEP_K_Inp ((PEP_K_On&2)!=0) - - /* IERS polar motion (ÉÓÔÏÞÎÉË: ftp://maia.usno.navy.mil/ser7/ser7.dat) */ - double xpol, ypol; -#define polarX (sdt->xpol) /* X-ÐÏÐÒÁ×Ëa ÐÏÌÏÖ.ÐÏÌÀÓÁ */ -#define polarY (sdt->ypol) /* Y-ÐÏÐÒÁ×Ëa ÐÏÌÏÖ.ÐÏÌÀÓÁ */ - - double jdate, eetime; -#define JDate (sdt->jdate) /* ÔÅËÕÝÁÑ ÀÌÉÁÎÓËÁÑ ÄÁÔÁ */ -#define EE_time (sdt->eetime) /* ÐÏÐÒÁ×.Ú×.×Ò. ÚÁ "Equation of the Equinoxes" */ - - /* ÅÝÅ ××ÏÄ ÍÅÔÅÏ-ÄÁÎÎÙÈ */ - double val_hmd, inp_hmd; -#define val_Hmd (sdt->val_hmd) /* ÚÎÁÞÅÎÉÅ ×ÌÁÖÎÏÓÔÉ (%) */ -#define inp_Hmd (sdt->val_hmd) /* ÒÕÞÎÏÊ ××ÏÄ */ - - /* ÐÏÌÏÖÅÎÉÅ ÞÅÒ×ÑËÁ (ÐÏÄ×ÅÓËÁ) */ - double worm_a, worm_z; -#define worm_A (sdt->worm_a) /* ÐÏÌÏÖÅÎÉÅ ÐÏÄ×ÅÓËÉ A (ÍËÍ) */ -#define worm_Z (sdt->worm_z) /* ÐÏÌÏÖÅÎÉÅ ÐÏÄ×ÅÓËÉ Z (ÍËÍ) */ - - /* ÆÌÁÇÉ ÂÌÏËÉÒÏ×ËÉ ÕÐÒÁ×ÌÅÎÉÑ ÕÚÌÁÍÉ */ - __uint32_t lock_flags; -#define LockFlags (sdt->lock_flags) -#define Lock_A 0x01 -#define Lock_Z 0x02 -#define Lock_P 0x04 -#define Lock_F 0x08 -#define Lock_D 0x10 -#define A_Locked (LockFlags&Lock_A) -#define Z_Locked (LockFlags&Lock_Z) -#define P_Locked (LockFlags&Lock_P) -#define F_Locked (LockFlags&Lock_F) -#define D_Locked (LockFlags&Lock_D) - - /* ÔÒÅÂÕÅÍÁÑ ÓËÏÒÏÓÔØ ÐÒÉ×ÏÄÁ ËÕÐÏÌÁ (ÄÌÑ ÕÐÒ-Ñ SEW-ÐÒÉ×ÏÄÁÍÉ)*/ - int sew_dome_speed; /* ÐÏËÁ ÔÏÖÅ ÞÔÏ É Dome_State */ -#define Dome_Speed (sdt->sew_dome_speed) /* Ô.Å. D_Lplus,D_Lminus,.... */ - -/* ÎÏÍÅÒ SEW-Ä×ÉÖËÁ ËÕÐÏÌÁ (ÄÌÑ ÉÎÄÉËÁÃÉÉ)*/ - int sew_dome_num; -#define DomeSEW_N (sdt->sew_dome_num) - -/* ÐÁÒÁÍÅÔÒÙ ×ÙÂÒÁÎÎÏÇÏ(DomeSEW_N) SEW-ËÏÎÔÒÏÌÌÅÒÁ ËÕÐÏÌÁ*/ -struct SEWdata sewdomedrv; -#define statusSEWD (sdt->sewdomedrv.status) /*ÓÏÓÔÏÑÎÉÅ ËÏÎÔÒÏÌÌÅÒÁ*/ -#define speedSEWD (sdt->sewdomedrv.set_speed) /*ÕÓÔÁÎÏ×ÌÅÎÎÁÑ ÓËÏÒÏÓÔØ ÏÂ/ÍÉÎ (rpm)*/ -#define vel_SEWD (sdt->sewdomedrv.mes_speed) /*ÉÚÍÅÒÅÎÎÁÑ ÓËÏÒÏÓÔØ ÏÂ/ÍÉÎ (rpm)*/ -#define currentSEWD (sdt->sewdomedrv.current) /*ÔÏË (á)*/ -#define indexSEWD (sdt->sewdomedrv.index) /*ÎÏÍÅÒ ÐÁÒÁÍÅÔÒÁ*/ -#define valueSEWD (sdt->sewdomedrv.value.l) /*ËÏÄ ÚÎÁÞÅÎÉÑ ÐÁÒÁÍÅÔÒÁ*/ - -/* ÉÎÆÏÒÍÁÃÉÑ PEP-ËÏÎÔÒÏÌÌÅÒÁ ËÕÐÏÌÁ */ - uint pep_code_di, pep_code_do; -#define PEP_code_Din (sdt->pep_code_di) /* ËÏÄ ÐÒÉÎÑÔÙÊ ÉÚ PEP-ËÕÐÏÌÁ */ -#define PEP_Dome_SEW_Ok 0x200 -#define PEP_Dome_Cable_Ok 0x100 -#define PEP_code_Dout (sdt->pep_code_do) /* ËÏÄ ×ÙÄÁ×ÁÅÍÙÊ × PEP-ËÕÐÏÌÁ */ -#define PEP_Dome_SEW_On 0x10 -#define PEP_Dome_SEW_Off 0x20 - -}; - -#ifndef BTA_MODULE -struct BTA_Data *sdt; -#else -extern struct BTA_Data *sdt; -#endif - -struct BTA_Local { /* ÓÔÒÕËÔÕÒÁ ÌÏËÁÌØÎÙÈ ÄÁÎÎÙÈ */ - unsigned char reserve[120]; /* Ó×ÏÂÏÄÎÏÅ ÍÅÓÔÏ ÄÌÑ ÒÁÓÛÉÒÅÎÉÑ ÇÌÏÂÁÌØÎÏÊ ÏÂÌÁÓÔÉ */ - /* (ÎÁ ÇÌÏÂÁÌØÎÕÀ ÏÂÌÁÓÔØ ÒÅÚÅÒ×ÉÒÕÅÍ 1500 ÂÁÊÔ) */ - double pr_oil_a,pr_oil_z,pr_oil_t; -#define PressOilA (sdtl->pr_oil_a) /* äÁ×ÌÅÎÉÅ × ÍÁÓÌÏÐÒÏ×ÏÄÅ A (íðÁ) */ -#define PressOilZ (sdtl->pr_oil_z) /* äÁ×ÌÅÎÉÅ × ÍÁÓÌÏÐÒÏ×ÏÄÅ Z (íðÁ) */ -#define PressOilTank (sdtl->pr_oil_t) /* äÁÔÞÉË ÕÒÏ×ÎÑ ÍÁÓÌÁ × ÂÁËÅ(ëðÁ) */ - double t_oil_1,t_oil_2; -#define OilTemper1 (sdtl->t_oil_1) /* ôÅÍÐÅÒÁÔÕÒÁ ÍÁÓÌÁ */ -#define OilTemper2 (sdtl->t_oil_2) /* ôÅÍÐÅÒÁÔÕÒÁ ÏÈÌÁÖÄÁÀÝÅÊ ×ÏÄÙ */ -}; - -#ifndef BTA_MODULE -struct BTA_Local *sdtl; /* ËÏÎÅà ÇÌÏÂÁÌØÎÙÈ, ÎÁÞÁÌÏ ÌÏËÁÌØÎÙÈ ÄÁÎÎÙÈ */ -#else -extern struct BTA_Local *sdtl; -#endif - -#define ClientSide 0 -#define ServerSide 1 - -#ifndef BTA_MODULE -static void bta_data_init(); -static int bta_data_check(); -static void bta_data_close(); - -/* ÏÐÉÓÁÎÉÅ ÂÌÏËÁ ÄÁÎÎÙÈ ÁÌÇÏÒÉÔÍÁ ÕÐÒÁ×ÌÅÎÉÑ ("ÇÌÏÂÁÌØÎÁÑ ÏÂÌÁÓÔØ") */ -struct SHM_Block sdat = { -{'S','d','a','t',0},sizeof(struct BTA_Data),2048,0444,SHM_RDONLY,bta_data_init,bta_data_check,bta_data_close,0,-1,NULL -}; -#else -extern struct SHM_Block sdat; -#endif - -#ifndef BTA_MODULE -/* ÉÎÉÃÉÁÌÉÚÁÃÉÑ ÄÁÎÎÙÈ ÁÌÇÏÒÉÔÍÁ ÕÐÒÁ×ÌÅÎÉÑ (ÏÂÎÕÌÅÎÉÅ "ÇÌÏÂÁÌØÎÏÊ ÏÂÌÁÓÔÉ") */ -static void bta_data_init() { - int i; - sdt = (struct BTA_Data *)sdat.addr; - sdtl = (struct BTA_Local *)(sdat.addr+sizeof(struct BTA_Data)); - if(sdat.side == ClientSide) { - if(sdt->magic != sdat.key.code) { - fprintf(stderr,"Wrong shared data (maybe server turned off)\n"); - /*exit(1);*/ - } - if(sdt->version == 0) { - fprintf(stderr,"Null shared data version (maybe server turned off)\n"); - /*exit(1);*/ - } - else if(sdt->version != BTA_Data_Ver) { - fprintf(stderr,"Wrong shared data version: I'am - %d, but server - %d ...\n", - BTA_Data_Ver, sdt->version ); - /*exit(1);*/ - } - if(sdt->size != sdat.size) { - if(sdt->size > sdat.size) { - /* ÎÏ ËÌÉÅÎÔ ÉÍÅÅÔ ÐÒÁ×Ï ÉÓÐÏÌØÚÏ×ÁÔØ ÎÁÞÁÌØÎÕÀ ÞÁÓÔØ ÄÁÎÎÙÈ */ - fprintf(stderr,"Wrong shared area size: I needs - %d, but server - %d ...\n", - sdat.size, sdt->size ); - } else { - /* "ÚÁÌÅÚÁÎÉÅ" × ÐÕÓÔÕÀ ÒÅÚÅÒ×ÎÕÀ ÞÁÓÔØ ÔÅÐÅÒØ ÔÏÖÅ */ - /* ÂÕÄÅÍ ÏÓÔÁ×ÌÑÔØ ÎÁ ÓÏ×ÅÓÔÉ Á×ÔÏÒÁ ËÌÉÅÎÔÁ! */ - fprintf(stderr,"Attention! Too little shared data structure!\n"); - sleep(1); - fprintf(stderr,"I needs - %d, but server gives only %d ...\n", - sdat.size, sdt->size ); - sleep(1); - fprintf(stderr,"May be server's version too old!?\n"); - /* exit(1); */ - - } - } - return; - } - /* ServerSide */ - if(sdt->magic != sdat.key.code || - sdt->version != BTA_Data_Ver || - sdt->size != sdat.size) { - - for(i=0; imagic = sdat.key.code; - sdt->version = BTA_Data_Ver; - sdt->size = sdat.size; - ServPID = 0; - UseModel = NoModel; - ClockType = Ch7_15; - Sys_Mode = SysStop; - Sys_Target = TagPosition; - Tel_Focus = Prime; - Tel_Hardware = Hard_On; - Tel_Mode = Automatic; - Az_Mode = Rev_Off; - P2_State = P2_Mode = P2_Off; - Foc_State = Foc_Off; - Dome_State = D_Off; - Pos_Corr = PC_On; - TrkOk_Mode = UseDiffVel | UseDiffAZ ; - InpAlpha=InpDelta= 0.; - SrcAlpha=SrcDelta= 0.; - VelAlpha=VelDelta= 0.; - CurAlpha=CurDelta= 0.; - InpAzim=InpZdist = 0.; - Diff_A=Diff_Z=Diff_P=0.0; - pos_cor_A=pos_cor_Z=refract_Z = 0.; - tel_cor_A=tel_cor_Z=tel_ref_Z = 0.; - vel_objA=vel_objZ=vel_objP = 0.; - diff_vA=diff_vZ=diff_vP=0.; - speedA = speedZ = speedP = 0.; - req_speedA = req_speedZ = req_speedP = 0.; - mod_vel_A=mod_vel_Z=mod_vel_P=mod_vel_F=mod_vel_D=0.; - code_KOST = 0; - M_time = S_time = L_time = 0.; - ppndd_A=ppndd_Z=ppndd_P=ppndd_B=0; - dup_A=dup_Z=dup_P=dup_F=dup_D=0; - low_A=low_Z=low_P=low_F=low_D=0; - code_A=code_Z=code_P=code_B=code_F=code_D=code_T1=code_T2=code_T3=code_Wnd=0; - val_A=val_Z=val_P=val_B=val_F=val_D=val_T1=val_T2=val_T3=val_Wnd=val_Alp=val_Del=0.; - vel_A=vel_Z=vel_P=vel_F=vel_D=0.; - for(i=0; imagic == sdat.key.code) && (sdt->version == BTA_Data_Ver) ); -} -static void bta_data_close() { - if(sdat.side == ServerSide) { - sdt->magic = 0; - sdt->version = 0; - } -} - -/* ÂÌÏË ÉÎÆÏÒÍÁÃÉÏÎÎÙÈ ÓÏÏÂÝÅÎÉÊ ??? */ -/*struct SHM_Block info = {{'I','n','f','o',0},1024,1024,0444,SHM_RDONLY,NULL,NULL,NULL,0,-1,NULL};*/ - -/* Allocate shared memory segment */ -static int get_shm_block( struct SHM_Block *sb, int server) { - int getsize = (server)? sb->maxsize : sb->size; - - /* first try to find existing one */ - sb->id = shmget(sb->key.code, getsize, sb->mode); - - if (sb->id<0 && errno==ENOENT && server) { - /* if no - try to create a new one */ - int cresize = sb->maxsize; - if(sb->size > cresize) { - fprintf(stderr,"Wrong shm maxsize(%d) < realsize(%d)\n",sb->maxsize,sb->size); - cresize = sb->size; - } - sb->id = shmget(sb->key.code, cresize, IPC_CREAT|IPC_EXCL|sb->mode); - } - if (sb->id<0) { - char msg[80]; - if(server) - sprintf(msg,"Can't create shared memory segment '%s'",sb->key.name); - else - sprintf(msg,"Can't find shared segment '%s' (maybe no server process) ",sb->key.name); - perror(msg); - return 0; - } - /* attach it to our memory space */ - sb->addr = (unsigned char *)shmat ( sb->id, NULL, sb->atflag ); - - if ((int)(sb->addr) == -1) { - char msg[80]; - sprintf(msg,"Can't attach shared memory segment '%s'",sb->key.name); - perror(msg); - return 0; - } - if(server) { - if((shmctl(sb->id, SHM_LOCK, NULL) < 0) < 0) { - char msg[80]; - sprintf(msg,"Can't prevents swapping of shared memory segment '%s'",sb->key.name); - perror(msg); - return 0; - } - } - fprintf(stderr,"Create&attach shared memory segment '%s' %dbytes at %x \n", - sb->key.name, sb->size, (uint)sb->addr); - - sb->side = server; - - if(sb->init!=NULL) - sb->init(); - return 1; -} -static int close_shm_block( struct SHM_Block *sb) { - int ret; - if(sb->close != NULL) - sb->close(); - if(sb->side == ServerSide) { -// ret = shmctl(sb->id, SHM_UNLOCK, NULL); - ret = shmctl(sb->id, IPC_RMID, NULL); - } - ret = shmdt (sb->addr); - return(ret); -} -#endif - -static int check_shm_block( struct SHM_Block *sb) { - if(sb->check != NULL) - return(sb->check()); - else return(0); -} - -#ifndef BTA_MODULE -int snd_id=-1; /* ÔÅËÕÝÉÊ (É ÅÄÉÎÓÔ×ÅÎÎÙÊ?) ËÁÎÁÌ ÏÔÓÙÌËÉ ËÏÍÁÎÄ ËÌÉÅÎÔÁ */ -int cmd_src_pid=0; /* ÎÏÍÅÒ ÐÒÏÃÅÓÓÁ ÉÓÔÏÞÎÉËÁ ÄÌÑ ïäîïê ÓÌÅÄ.ËÏÍÁÎÄÙ */ -__uint32_t cmd_src_ip=0; /* IP-ÁÄÒ. ÉÓÔÏÞÎÉËÁ ÄÌÑ ïäîïê ÓÌÅÄ.ËÏÍÁÎÄÙ */ -#else -extern int snd_id; -extern int cmd_src_pid; -extern __uint32_t cmd_src_ip; -#endif - -#ifndef BTA_MODULE -/* Create|Find command queue */ -static void get_cmd_queue( struct CMD_Queue *cq, int server) { - if (!server && cq->id>=0) { /* if already in use */ - snd_id = cq->id; /* set current... */ - return; - } - /* first try to find existing one */ - cq->id = msgget(cq->key.code, cq->mode); - if (cq->id<0 && errno==ENOENT && server) - /* if no - try to create a new one */ - cq->id = msgget(cq->key.code, IPC_CREAT|IPC_EXCL|cq->mode); - if (cq->id<0) { - char msg[80]; - if(server) - sprintf(msg,"Can't create comand queue '%s'",cq->key.name); - else - sprintf(msg,"Can't find comand queue '%s' (maybe no server process) ",cq->key.name); - perror(msg); - return; - } - cq->side = server; - if (server) { - char buf[120]; /* ×ÙÂÒÏÓÉÔØ ×ÓÅ ËÏÍÁÎÄÙ ÉÚ ÏÞÅÒÅÄÉ */ - while(msgrcv(cq->id, (struct msgbuf *)buf, 112, 0, IPC_NOWAIT)>0); - } else - snd_id = cq->id; - cq->acckey = 0; -} -#endif - -/* ÕÓÔÁÎÏ×ËÁ ËÌÀÞÁ ÄÏÓÔÕÐÁ × ÔÅË. ËÁÎÁÌÅ */ -static void set_acckey(uint newkey) { - if (snd_id<0) return; - if(ucmd.id==snd_id) ucmd.acckey=newkey; - else if(ocmd.id==snd_id) ocmd.acckey=newkey; - else if(mcmd.id==snd_id) mcmd.acckey=newkey; -} - -/* ÕÓÔÁÎÏ×ËÁ ÄÁÎÎÙÈ ÉÓÔÏÞÎÉËÁ ÄÌÑ ïäîïê ÓÌÅÄ.ËÏÍÁÎÄÙ */ -/* ÅÓÌÉ ÎÅ ÐÏÄÈÏÄÑÔ ÕÍÏÌÞÁÎÉÑ: IP=0(ÌÏËÁÌØÎÁÑ ËÏÍÁÎÄÁ) É PID ÔÅËÕÝ.ÐÒÏÃÅÓÓÁ */ -static void set_cmd_src(__uint32_t ip, int pid) { - cmd_src_pid = pid; - cmd_src_ip = ip; -} - -/* ÓÔÒÕËÔÕÒÁ ÓÏÏÂÝÅÎÉÑ */ -struct my_msgbuf { - __int32_t mtype; /* type of message */ - __uint32_t acckey; /* ËÌÀÞ ÄÏÓÔÕÐÁ ËÌÉÅÎÔÁ */ - __uint32_t src_pid; /* ÎÏÍÅÒ ÐÒÏÃÅÓÓÁ ÉÓÔÏÞÎÉËÁ */ - __uint32_t src_ip; /* IP-ÁÄÒ. ÉÓÔÏÞÎÉËÁ, =0 - ÌÏËÁÌØÎÁÑ ËÏÍÁÎÄÁ */ - char mtext[100]; /* message text */ -}; -/* ÏÔÓÙÌËÁ ËÏÍÁÎÄ ËÌÉÅÎÔÁ Ë ÓÅÒ×ÅÒÕ */ -static void send_cmd(int cmd_code, char *buf, int size) { - struct my_msgbuf mbuf; - - if (snd_id<0) return; - if (size>100) size=100; - if (cmd_code>0) - mbuf.mtype = cmd_code; - else - return; - if(ucmd.id==snd_id) mbuf.acckey=ucmd.acckey; - else if(ocmd.id==snd_id) mbuf.acckey=ocmd.acckey; - else if(mcmd.id==snd_id) mbuf.acckey=mcmd.acckey; - - mbuf.src_pid = cmd_src_pid? cmd_src_pid : getpid(); - mbuf.src_ip = cmd_src_ip; - cmd_src_pid = cmd_src_ip = 0; - - if(size>0) - memcpy( mbuf.mtext, buf, size); - else { - mbuf.mtext[0] = 0; - size = 1; - } - msgsnd( snd_id, (struct msgbuf *)&mbuf, size+12, IPC_NOWAIT); -} -static void send_cmd_noarg(int cmd_code) { - send_cmd(cmd_code, NULL, 0); -} -static void send_cmd_str(int cmd_code, char *arg) { - send_cmd(cmd_code, arg, strlen(arg)+1); -} -static void send_cmd_i1(int cmd_code, int arg1) { - send_cmd(cmd_code, (char *)&arg1, sizeof(int)); -} -static void send_cmd_i2(int cmd_code, int arg1, int arg2) { - int ibuf[2]; - ibuf[0] = arg1; - ibuf[1] = arg2; - send_cmd(cmd_code, (char *)ibuf, 2*sizeof(int)); -} -static void send_cmd_i3(int cmd_code, int arg1, int arg2, int arg3) { - int ibuf[3]; - ibuf[0] = arg1; - ibuf[1] = arg2; - ibuf[2] = arg3; - send_cmd(cmd_code, (char *)ibuf, 3*sizeof(int)); -} -static void send_cmd_i4(int cmd_code, int arg1, int arg2, int arg3, int arg4) { - int ibuf[4]; - ibuf[0] = arg1; - ibuf[1] = arg2; - ibuf[2] = arg3; - ibuf[3] = arg4; - send_cmd(cmd_code, (char *)ibuf, 4*sizeof(int)); -} -static void send_cmd_d1(int cmd_code, double arg1) { - send_cmd(cmd_code, (char *)&arg1, sizeof(double)); -} -static void send_cmd_d2(int cmd_code, double arg1, double arg2) { - double dbuf[2]; - dbuf[0] = arg1; - dbuf[1] = arg2; - send_cmd(cmd_code, (char *)dbuf, 2*sizeof(double)); -} -static void send_cmd_i1d1(int cmd_code, int arg1, double arg2) { - struct { - int ival; - double dval; - } buf; - buf.ival = arg1; - buf.dval = arg2; - send_cmd(cmd_code, (char *)&buf, sizeof(buf)); -} -static void send_cmd_i2d1(int cmd_code, int arg1, int arg2, double arg3) { - struct { - int ival[2]; - double dval; - } buf; - buf.ival[0] = arg1; - buf.ival[1] = arg2; - buf.dval = arg3; - send_cmd(cmd_code, (char *)&buf, sizeof(buf)); -} -static void send_cmd_i3d1(int cmd_code, int arg1, int arg2, int arg3, double arg4) { - struct { - int ival[3]; - double dval; - } buf; - buf.ival[0] = arg1; - buf.ival[1] = arg2; - buf.ival[2] = arg3; - buf.dval = arg4; - send_cmd(cmd_code, (char *)&buf, sizeof(buf)); -} - -static void encode_lev_passwd(char *passwd, int nlev, uint *keylev, uint *codlev) { - char salt[4]; - char *encr; - union { - uint ui; - char c[4]; - } key,cod; - sprintf(salt,"L%1d",nlev); - encr = (char *)crypt(passwd, salt); - cod.c[0] = encr[2]; - key.c[0] = encr[3]; - cod.c[1] = encr[4]; - key.c[1] = encr[5]; - cod.c[2] = encr[6]; - key.c[2] = encr[7]; - cod.c[3] = encr[8]; - key.c[3] = encr[9]; - *keylev = key.ui; - *codlev = cod.ui; -} - -static int find_lev_passwd(char *passwd, uint *keylev, uint *codlev) { - int nlev; - for(nlev=5; nlev>0; nlev--) { - encode_lev_passwd(passwd, nlev, keylev, codlev); - if(nlev == 1 && code_Lev1 == *codlev) break; - if(nlev == 2 && code_Lev2 == *codlev) break; - if(nlev == 3 && code_Lev3 == *codlev) break; - if(nlev == 4 && code_Lev4 == *codlev) break; - if(nlev == 5 && code_Lev5 == *codlev) break; - } - return(nlev); -} - -static int check_lev_passwd(char *passwd) { - uint keylev,codlev; - int nlev; - nlev = find_lev_passwd(passwd, &keylev, &codlev); - if(nlev>0) set_acckey(keylev); - return(nlev); -} - -#pragma GCC diagnostic pop - -#endif // __BTA_SHDATA_H__ diff --git a/stepper_motion/client-p2/cmdlnopts.c b/stepper_motion/client-p2/cmdlnopts.c deleted file mode 100644 index 328fb3a..0000000 --- a/stepper_motion/client-p2/cmdlnopts.c +++ /dev/null @@ -1,120 +0,0 @@ -/* - * cmdlnopts.c - the only function that parse cmdln args and returns glob parameters - * - * Copyright 2013 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#include -#include -#include -#include "cmdlnopts.h" - -/* - * here are global parameters initialisation - */ -glob_pars G; // internal global parameters structure -int help = 0; // whether to show help string - -glob_pars Gdefault = { - .serialdev = "/dev/ttyACM0", - .gotopos = -1000., - .relmove = 0., -}; - -#ifndef N_ -#define N_(x) (x) -#endif - -#ifndef _ -#define _(x) (x) -#endif - -bool get_angle(double *dest, char *src){ - double A = 0., sign = 1.; - int d,m; -// printf("arg: %s\n", src); - if(myatod(&A, src, arg_double)){ // angle in seconds - *dest = A; - return true; - }else if(3 == sscanf(src, "%d:%d:%lf", &d, &m, &A)){ - if(d > -361 && d < 361 && m > -1 && m < 60 && A > -0.1 && A < 60.){ - if(d < 0) sign = -1.; - *dest = sign*A + sign*60.*m + 3600.*d; - return true; - } - }else if(2 == sscanf(src, "%d:%lf", &m, &A)){ - if(m > -60 && m < 60 && A > -0.1 && A < 60.){ - if(m < 0) sign = -1.; - *dest = sign*A + 60.*m; - return true; - } - } - fprintf(stderr, "Wrong angle format [%s], need: ss.ss, mm:ss.ss or dd:mm:ss.ss\n", src); - return false; -} -#ifndef _U_ -#define _U_ __attribute__((__unused__)) -#endif -bool ang_goto(void *arg, _U_ int N){ - return get_angle(&G.gotopos, arg); -} - -bool ang_gorel(void *arg, _U_ int N){ - return get_angle(&G.relmove, arg); -} - -/* - * Define command line options by filling structure: - * name has_arg flag val type argptr help -*/ -myoption cmdlnopts[] = { - /// "ÏÔÏÂÒÁÚÉÔØ ÜÔÏ ÓÏÏÂÝÅÎÉÅ" - {"help", 0, NULL, 'h', arg_int, APTR(&help), N_("show this help")}, - /// "ÐÕÔØ Ë ÕÓÔÒÏÊÓÔ×Õ ÍÉËÒÏËÏÎÔÒÏÌÌÅÒÁ" - {"serialdev",1, NULL, 'd', arg_string, APTR(&G.serialdev), N_("path to MCU device")}, - {"goto", 1, NULL, 'g', arg_function,APTR(ang_goto), N_("go to given position")}, - {"relative",1, NULL, 'r', arg_function,APTR(ang_gorel), N_("go relative current position")}, - end_option -}; - - -/** - * Parse command line options and return dynamically allocated structure - * to global parameters - * @param argc - copy of argc from main - * @param argv - copy of argv from main - * @return allocated structure with global parameters - */ -glob_pars *parse_args(int argc, char **argv){ - int i; - void *ptr; - ptr = memcpy(&G, &Gdefault, sizeof(G)); assert(ptr); - // format of help: "Usage: progname [args]\n" - /// "éÓÐÏÌØÚÏ×ÁÎÉÅ: %s [ÁÒÇÕÍÅÎÔÙ]\n\n\tçÄÅ ÁÒÇÕÍÅÎÔÙ:\n" - change_helpstring(_("Usage: %s [args]\n\n\tWhere args are:\n")); - // parse arguments - parseargs(&argc, &argv, cmdlnopts); - if(help) showhelp(-1, cmdlnopts); - if(argc > 0){ - /// "éÇÎÏÒÉÒÕÀ ÁÒÇÕÍÅÎÔ[Ù]:" - printf("\n%s\n", _("Ignore argument[s]:")); - for (i = 0; i < argc; i++) - printf("\t%s\n", argv[i]); - } - return &G; -} - diff --git a/stepper_motion/client-p2/cmdlnopts.h b/stepper_motion/client-p2/cmdlnopts.h deleted file mode 100644 index 33dac79..0000000 --- a/stepper_motion/client-p2/cmdlnopts.h +++ /dev/null @@ -1,40 +0,0 @@ -/* - * cmdlnopts.h - comand line options for parseargs - * - * Copyright 2013 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CMDLNOPTS_H__ -#define __CMDLNOPTS_H__ - -#include "parseargs.h" - -/* - * here are some typedef's for global data - */ - -typedef struct{ - char *serialdev; // input device - double gotopos; // go to given angle - double relmove; // move relative current position -}glob_pars; - -glob_pars *parse_args(int argc, char **argv); - -#endif // __CMDLNOPTS_H__ diff --git a/stepper_motion/client-p2/main.c b/stepper_motion/client-p2/main.c deleted file mode 100644 index 0d1191a..0000000 --- a/stepper_motion/client-p2/main.c +++ /dev/null @@ -1,284 +0,0 @@ -/* - * main.c - main file - * - * Copyright 2015 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#include // tcsetattr -#include // tcsetattr, close, read, write -#include // ioctl -#include // printf, getchar, fopen, perror -#include // exit -#include // read -#include // read -#include // signal -#include // time -#include // memcpy -#include // int types -#include // gettimeofday -#include // assert -#include // threads - -#include "bta_shdata.h" -#include "cmdlnopts.h" - -#ifndef _U_ -#define _U_ __attribute__((__unused__)) -#endif - -#ifndef fabs -#define fabs(x) ((x > 0.) ? x : -x) -#endif - -// scale: how much steps there is in one angular second -const double steps_per_second = 2.054; - -// end-switch at 8degr -#define MIN_RESTRICT_ANGLE (29000.) -// end-switch at 100degr -#define MAX_RESTRICT_ANGLE (360000.) - -#define BUFLEN 1024 - -glob_pars *Global_parameters = NULL; - -int is_running = 1; // ==0 to exit -int BAUD_RATE = B115200; -struct termio oldtty, tty; // TTY flags -struct termios oldt, newt; // terminal flags -int comfd; // TTY fd - -#define DBG(...) do{fprintf(stderr, __VA_ARGS__);}while(0) - -/** - * function for different purposes that need to know time intervals - * @return double value: time in seconds - */ -double dtime(){ - double t; - struct timeval tv; - gettimeofday(&tv, NULL); - t = tv.tv_sec + ((double)tv.tv_usec)/1e6; - return t; -} - -/** - * Exit & return terminal to old state - * @param ex_stat - status (return code) - */ -void quit(int ex_stat){ - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); // return terminal to previous state - ioctl(comfd, TCSANOW, &oldtty ); // return TTY to previous state - close(comfd); - printf("Exit! (%d)\n", ex_stat); - exit(ex_stat); -} - -/** - * Open & setup TTY, terminal - */ -void tty_init(){ - // terminal without echo - tcgetattr(STDIN_FILENO, &oldt); - newt = oldt; - newt.c_lflag &= ~(ICANON | ECHO); - if(tcsetattr(STDIN_FILENO, TCSANOW, &newt) < 0) quit(-2); - printf("\nOpen port...\n"); - if ((comfd = open(Global_parameters->serialdev,O_RDWR|O_NOCTTY|O_NONBLOCK)) < 0){ - fprintf(stderr,"Can't use port %s\n",Global_parameters->serialdev); - quit(1); - } - printf(" OK\nGet current settings...\n"); - if(ioctl(comfd,TCGETA,&oldtty) < 0) exit(-1); // Get settings - tty = oldtty; - tty.c_lflag = 0; // ~(ICANON | ECHO | ECHOE | ISIG) - tty.c_oflag = 0; - tty.c_cflag = BAUD_RATE|CS8|CREAD|CLOCAL; // 9.6k, 8N1, RW, ignore line ctrl - tty.c_cc[VMIN] = 0; // non-canonical mode - tty.c_cc[VTIME] = 5; - if(ioctl(comfd,TCSETA,&tty) < 0) exit(-1); // set new mode - printf(" OK\n"); - tcsetattr(STDIN_FILENO, TCSANOW, &newt); -} - -/** - * read tty - * @param buff (o) - buffer for messages readed from tty - * @param length (io) - buff's length (return readed len or 0) - * @return 1 if something was readed here or there - */ -int read_tty(char *buff, size_t *length){ - ssize_t L; - size_t buffsz = *length; - struct timeval tv; - int sel, retval = 0; - fd_set rfds; - FD_ZERO(&rfds); - FD_SET(STDIN_FILENO, &rfds); - FD_SET(comfd, &rfds); - tv.tv_sec = 0; tv.tv_usec = 100000; - sel = select(comfd + 1, &rfds, NULL, NULL, &tv); - if(sel > 0){ - if(FD_ISSET(comfd, &rfds)){ - if((L = read(comfd, buff, buffsz)) < 1){ // disconnect or other troubles - fprintf(stderr, "USB error or disconnected!\n"); - quit(1); - }else{ - if(L == 0){ // USB disconnected - fprintf(stderr, "USB disconnected!\n"); - quit(1); - } - // all OK continue reading - *length = (size_t) L; - retval = 1; - } - }else{ - *length = 0; - } - } - return retval; -} - -void print_P2(){ - int d, m; - double s = val_P; - d = ((int)s / 3600) % 360; - s -= 3600. * d; - m = s / 60; - s -= 60. * m; - printf("P2 value: %02d:%02d:%03.1f\n", d, m, s); -} - -/* -void help(){ - P("G\tgo to N steps\n"); - P("H\tshow this help\n"); - P("P\tset stepper period (us)\n"); - P("S\tstop motor\n"); - P("T\tshow current approx. time\n"); - P("W\tshow current steps value\n"); - P("X\tshow current stepper period\n"); -} -*/ - -void write_tty(char *str){ - while(*str){ - write(comfd, str++, 1); - } -} - -/** - * give command to move P2 on some angle - * @param rel == 1 for relative moving - * @param angle - angle in seconds - */ -void move_P2(int rel, double angle){ - double curP = val_P, targP; - char buf[256]; - if(fabs(angle) < 1.) return; // don't move to such little degrees - if(curP > MIN_RESTRICT_ANGLE && curP < MAX_RESTRICT_ANGLE){ - fprintf(stderr, "Error: motor is in restricted area!\n"); - quit(-1); - } - if(rel) targP = curP + angle; - else targP = angle; - // check for restricted zone - if(targP > MIN_RESTRICT_ANGLE && targP < MAX_RESTRICT_ANGLE){ - fprintf(stderr, "Error: you want to move into restricted area!\n"); - quit(-10); - } - // now check preferred rotation direction - angle = targP - curP; - //printf("targP: %g, curP: %g, angle: %g\n", targP, curP, angle); - // 360degr = 1296000''; 180degr = 648000'' - if(angle < 0.) angle += 1296000.; - if(angle > 648000.){ // it's better to move in negative direction - angle -= 1296000.; - } - // convert angle into steps - angle *= steps_per_second; - _U_ size_t L = snprintf(buf, 256, "G%d\n", ((int)angle)); - //printf("BUF: %s\n", buf); - write_tty(buf); - //is_running = 0; - while(is_running); -} - -void *moving_thread(_U_ void *buf){ - if(Global_parameters->gotopos > 0.){ -//printf("gotoval: %g\n", Global_parameters->gotopos); - move_P2(0, Global_parameters->gotopos); - }else if(fabs(Global_parameters->relmove) > 1.){ // move relative current position -//printf("relval: %g\n", Global_parameters->relmove); - move_P2(1, Global_parameters->relmove); - } -// sleep(1); // give a little time for receiving messages -// is_running = 0; - return NULL; -} - -int main(int argc, char *argv[]){ - char buff[BUFLEN+1]; - pthread_t motor_thread; - size_t L; - Global_parameters = parse_args(argc, argv); - assert(Global_parameters != NULL); - if(!get_shm_block(&sdat, ClientSide) || !check_shm_block(&sdat)){ - fprintf(stderr, "Can't get SHM block!"); - return -1; - } - tty_init(); - signal(SIGTERM, quit); // kill (-15) - signal(SIGINT, quit); // ctrl+C - signal(SIGQUIT, SIG_IGN); // ctrl+\ . - signal(SIGTSTP, SIG_IGN); // ctrl+Z - setbuf(stdout, NULL); - double t, t0 = 0; - double p_old = -400.; // impossible value for printing P2 val on first run - - if(pthread_create(&motor_thread, NULL, moving_thread, NULL)){ - /// "Ðе могу Ñоздать поток Ð´Ð»Ñ Ð·Ð°Ñ…Ð²Ð°Ñ‚Ð° видео" - fprintf(stderr, "Can't create readout thread\n"); - quit(-1); - } - while(is_running){ - L = BUFLEN; - if((t = dtime()) - t0 > 1.){ // once per second (and on first run) check P2 position - if(fabs(val_P - p_old) > 0.1){ - p_old = val_P; - print_P2(); - } - t0 = t; - } - if(read_tty(buff, &L)){ - if(L){ - buff[L] = 0; - printf("GOT: %s", buff); - if(strncmp(buff, "Stop", 4) == 0){ - is_running = 0; - sleep(1); - } - } - } - if(!check_shm_block(&sdat)){ - fprintf(stderr, "Corruption in SHM block!"); - quit(-2); - } - } - quit(0); - return 0; -} diff --git a/stepper_motion/client-p2/parseargs.c b/stepper_motion/client-p2/parseargs.c deleted file mode 100644 index 75e8cac..0000000 --- a/stepper_motion/client-p2/parseargs.c +++ /dev/null @@ -1,296 +0,0 @@ -/* - * parseargs.c - parsing command line arguments & print help - * - * Copyright 2013 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include // DBG -#include // getopt_long -#include // calloc, exit, strtoll -#include // assert -#include // strdup, strchr, strlen -#include // INT_MAX & so on -#include // gettext -#include // isalpha -#include "parseargs.h" - -// macro to print help messages -#ifndef PRNT - #define PRNT(x) gettext(x) -#endif - -char *helpstring = "%s\n"; - -/** - * Change standard help header - * MAY consist ONE "%s" for progname - * @param str (i) - new format - */ -void change_helpstring(char *s){ - int pcount = 0, scount = 0; - char *str = s; - // check `helpstring` and set it to default in case of error - for(; pcount < 2; str += 2){ - if(!(str = strchr(str, '%'))) break; - if(str[1] != '%') pcount++; // increment '%' counter if it isn't "%%" - else{ - str += 2; // pass next '%' - continue; - } - if(str[1] == 's') scount++; // increment "%s" counter - }; - if(pcount > 1 || pcount != scount){ // amount of pcount and/or scount wrong - fprintf(stderr, "Wrong helpstring!\n"); - exit(-1); - } - helpstring = s; -} - -/** - * Carefull atoll/atoi - * @param num (o) - returning value (or NULL if you wish only check number) - allocated by user - * @param str (i) - string with number must not be NULL - * @param t (i) - T_INT for integer or T_LLONG for long long (if argtype would be wided, may add more) - * @return TRUE if conversion sone without errors, FALSE otherwise - */ -bool myatoll(void *num, char *str, argtype t){ - long long tmp, *llptr; - int *iptr; - char *endptr; - assert(str); - assert(num); - tmp = strtoll(str, &endptr, 0); - if(endptr == str || *str == '\0' || *endptr != '\0') - return FALSE; - switch(t){ - case arg_longlong: - llptr = (long long*) num; - *llptr = tmp; - break; - case arg_int: - default: - if(tmp < INT_MIN || tmp > INT_MAX){ - fprintf(stderr, "Integer out of range\n"); - return FALSE; - } - iptr = (int*)num; - *iptr = (int)tmp; - } - return TRUE; -} - -// the same as myatoll but for double -// There's no NAN & INF checking here (what if they would be needed?) -bool myatod(void *num, const char *str, argtype t){ - double tmp, *dptr; - float *fptr; - char *endptr; - assert(str); - tmp = strtod(str, &endptr); - if(endptr == str || *str == '\0' || *endptr != '\0') - return FALSE; - switch(t){ - case arg_double: - dptr = (double *) num; - *dptr = tmp; - break; - case arg_float: - default: - fptr = (float *) num; - *fptr = (float)tmp; - break; - } - return TRUE; -} - -/** - * Get index of current option in array options - * @param opt (i) - returning val of getopt_long - * @param options (i) - array of options - * @return index in array - */ -int get_optind(int opt, myoption *options){ - int oind; - myoption *opts = options; - assert(opts); - for(oind = 0; opts->name && opts->val != opt; oind++, opts++); - if(!opts->name || opts->val != opt) // no such parameter - showhelp(-1, options); - return oind; -} - -/** - * Parse command line arguments - * ! If arg is string, then value will be strdup'ed! - * - * @param argc (io) - address of argc of main(), return value of argc stay after `getopt` - * @param argv (io) - address of argv of main(), return pointer to argv stay after `getopt` - * BE CAREFUL! if you wanna use full argc & argv, save their original values before - * calling this function - * @param options (i) - array of `myoption` for arguments parcing - * - * @exit: in case of error this function show help & make `exit(-1)` - */ -void parseargs(int *argc, char ***argv, myoption *options){ - char *short_options, *soptr; - struct option *long_options, *loptr; - size_t optsize, i; - myoption *opts = options; - // check whether there is at least one options - assert(opts); - assert(opts[0].name); - // first we count how much values are in opts - for(optsize = 0; opts->name; optsize++, opts++); - // now we can allocate memory - short_options = calloc(optsize * 3 + 1, 1); // multiply by three for '::' in case of args in opts - long_options = calloc(optsize + 1, sizeof(struct option)); - opts = options; loptr = long_options; soptr = short_options; - // fill short/long parameters and make a simple checking - for(i = 0; i < optsize; i++, loptr++, opts++){ - // check - assert(opts->name); // check name - if(opts->has_arg){ - assert(opts->type != arg_none); // check error with arg type - assert(opts->argptr); // check pointer - } - if(opts->type != arg_none) // if there is a flag without arg, check its pointer - assert(opts->argptr); - // fill long_options - // don't do memcmp: what if there would be different alignment? - loptr->name = opts->name; - loptr->has_arg = opts->has_arg; - loptr->flag = opts->flag; - loptr->val = opts->val; - // fill short options if they are: - if(!opts->flag){ - *soptr++ = opts->val; - if(opts->has_arg) // add ':' if option has required argument - *soptr++ = ':'; - if(opts->has_arg == 2) // add '::' if option has optional argument - *soptr++ = ':'; - } - } - // now we have both long_options & short_options and can parse `getopt_long` - while(1){ - int opt; - int oindex = 0, optind = 0; // oindex - number of option in argv, optind - number in options[] - if((opt = getopt_long(*argc, *argv, short_options, long_options, &oindex)) == -1) break; - if(opt == '?'){ - opt = optopt; - optind = get_optind(opt, options); - if(options[optind].has_arg == 1) showhelp(optind, options); // need argument - } - else{ - if(opt == 0 || oindex > 0) optind = oindex; - else optind = get_optind(opt, options); - } - opts = &options[optind]; - if(opt == 0 && opts->has_arg == 0) continue; // only long option changing integer flag - // now check option - if(opts->has_arg == 1) assert(optarg); - bool result = TRUE; - // even if there is no argument, but argptr != NULL, think that optarg = "1" - if(!optarg) optarg = "1"; - switch(opts->type){ - default: - case arg_none: - if(opts->argptr) *((int*)opts->argptr) = 1; // set argptr to 1 - break; - case arg_int: - result = myatoll(opts->argptr, optarg, arg_int); - break; - case arg_longlong: - result = myatoll(opts->argptr, optarg, arg_longlong); - break; - case arg_double: - result = myatod(opts->argptr, optarg, arg_double); - break; - case arg_float: - result = myatod(opts->argptr, optarg, arg_float); - break; - case arg_string: - result = (*((char **)opts->argptr) = strdup(optarg)); - break; - case arg_function: - result = ((argfn)opts->argptr)(optarg, optind); - break; - } - if(!result){ - showhelp(optind, options); - } - } - *argc -= optind; - *argv += optind; -} - -/** - * Show help information based on myoption->help values - * @param oindex (i) - if non-negative, show only help by myoption[oindex].help - * @param options (i) - array of `myoption` - * - * @exit: run `exit(-1)` !!! - */ -void showhelp(int oindex, myoption *options){ - // ATTENTION: string `help` prints through macro PRNT(), by default it is gettext, - // but you can redefine it before `#include "parseargs.h"` - int max_opt_len = 0; // max len of options substring - for right indentation - const int bufsz = 255; - char buf[bufsz+1]; - myoption *opts = options; - assert(opts); - assert(opts[0].name); // check whether there is at least one options - if(oindex > -1){ // print only one message - opts = &options[oindex]; - printf(" "); - if(!opts->flag && isalpha(opts->val)) printf("-%c, ", opts->val); - printf("--%s", opts->name); - if(opts->has_arg == 1) printf("=arg"); - else if(opts->has_arg == 2) printf("[=arg]"); - printf(" %s\n", PRNT(opts->help)); - exit(-1); - } - // header, by default is just "progname\n" - printf("\n"); - if(strstr(helpstring, "%s")) // print progname - printf(helpstring, __progname); - else // only text - printf("%s", helpstring); - printf("\n"); - // count max_opt_len - do{ - int L = strlen(opts->name); - if(max_opt_len < L) max_opt_len = L; - }while((++opts)->name); - max_opt_len += 14; // format: '-S , --long[=arg]' - get addition 13 symbols - opts = options; - // Now print all help - do{ - int p = sprintf(buf, " "); // a little indent - if(!opts->flag && isalpha(opts->val)) // .val is short argument - p += snprintf(buf+p, bufsz-p, "-%c, ", opts->val); - p += snprintf(buf+p, bufsz-p, "--%s", opts->name); - if(opts->has_arg == 1) // required argument - p += snprintf(buf+p, bufsz-p, "=arg"); - else if(opts->has_arg == 2) // optional argument - p += snprintf(buf+p, bufsz-p, "[=arg]"); - assert(p < max_opt_len); // there would be magic if p >= max_opt_len - printf("%-*s%s\n", max_opt_len+1, buf, PRNT(opts->help)); // write options & at least 2 spaces after - }while((++opts)->name); - printf("\n\n"); - exit(-1); -} diff --git a/stepper_motion/client-p2/parseargs.h b/stepper_motion/client-p2/parseargs.h deleted file mode 100644 index 0336e7c..0000000 --- a/stepper_motion/client-p2/parseargs.h +++ /dev/null @@ -1,106 +0,0 @@ -/* - * parseargs.h - headers for parcing command line arguments - * - * Copyright 2013 Edward V. Emelianoff - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __PARSEARGS_H__ -#define __PARSEARGS_H__ - -#include // bool -#include - -#ifndef TRUE - #define TRUE true -#endif - -#ifndef FALSE - #define FALSE false -#endif - -// macro for argptr -#define APTR(x) ((void*)x) - -// if argptr is a function: -typedef bool(*argfn)(void *arg, int N); - -/* - * type of getopt's argument - * WARNING! - * My function change value of flags by pointer, so if you want to use another type - * make a latter conversion, example: - * char charg; - * int iarg; - * myoption opts[] = { - * {"value", 1, NULL, 'v', arg_int, &iarg, "char val"}, ..., end_option}; - * ..(parse args).. - * charg = (char) iarg; - */ -typedef enum { - arg_none = 0, // no arg - arg_int, // integer - arg_longlong, // long long - arg_double, // double - arg_float, // float - arg_string, // char * - arg_function // parse_args will run function `bool (*fn)(char *optarg, int N)` -} argtype; - -/* - * Structure for getopt_long & help - * BE CAREFUL: .argptr is pointer to data or pointer to function, - * conversion depends on .type - * - * ATTENTION: string `help` prints through macro PRNT(), bu default it is gettext, - * but you can redefine it before `#include "parseargs.h"` - * - * if arg is string, then value wil be strdup'ed like that: - * char *str; - * myoption opts[] = {{"string", 1, NULL, 's', arg_string, &str, "string val"}, ..., end_option}; - * *(opts[1].str) = strdup(optarg); - * in other cases argptr should be address of some variable (or pointer to allocated memory) - * - * NON-NULL argptr should be written inside macro APTR(argptr) or directly: (void*)argptr - * - * !!!LAST VALUE OF ARRAY SHOULD BE `end_option` or ZEROS !!! - * - */ -typedef struct{ - // these are from struct option: - const char *name; // long option's name - int has_arg; // 0 - no args, 1 - nesessary arg, 2 - optionally arg - int *flag; // NULL to return val, pointer to int - to set its value of val (function returns 0) - int val; // short opt name (if flag == NULL) or flag's value - // and these are mine: - argtype type; // type of argument - void *argptr; // pointer to variable to assign optarg value or function `bool (*fn)(char *optarg, int N)` - char *help; // help string which would be shown in function `showhelp` or NULL -} myoption; - -// last string of array (all zeros) -#define end_option {0,0,0,0,0,0,0} - - -extern const char *__progname; - -void showhelp(int oindex, myoption *options); -void parseargs(int *argc, char ***argv, myoption *options); -void change_helpstring(char *s); -bool myatod(void *num, const char *str, argtype t); - -#endif // __PARSEARGS_H__ diff --git a/stepper_motion/hardware_ini.c b/stepper_motion/hardware_ini.c deleted file mode 100644 index 91bf8ce..0000000 --- a/stepper_motion/hardware_ini.c +++ /dev/null @@ -1,99 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); -/* - // Buttons: pull-up input - gpio_set_mode(BTNS_PORT, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, - BTN_S2_PIN | BTN_S3_PIN); - // turn on pull-up - gpio_set(BTNS_PORT, BTN_S2_PIN | BTN_S3_PIN); - // LEDS: opendrain output - gpio_set_mode(LEDS_PORT, GPIO_MODE_OUTPUT_2_MHZ, GPIO_CNF_OUTPUT_OPENDRAIN, - LED_D1_PIN | LED_D2_PIN); - // turn off LEDs - gpio_set(LEDS_PORT, LED_D1_PIN | LED_D2_PIN); - */ -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - -/* -// check buttons S2/S3 -void check_btns(){ - static uint8_t oldstate[2] = {1,1}; // old buttons state - uint8_t newstate[2], i; - static uint32_t Old_timer[2] = {0,0}; - newstate[0] = gpio_get(BTNS_PORT, BTN_S2_PIN) ? 1 : 0; - newstate[1] = gpio_get(BTNS_PORT, BTN_S3_PIN) ? 1 : 0; - for(i = 0; i < 2; i++){ - uint8_t new = newstate[i]; - // pause for 60ms - uint32_t O = Old_timer[i]; - if(O){ - if(Timer - O > 60 || O > Timer){ - P("Button S"); - usb_send('2' + i); - if(new) P("released"); - else P("pressed"); - newline(); - oldstate[i] = new; - Old_timer[i] = 0; - } - } - else if(new != oldstate[i]){ - Old_timer[i] = Timer; - } - } -} -*/ diff --git a/stepper_motion/hardware_ini.h b/stepper_motion/hardware_ini.h deleted file mode 100644 index 5e00745..0000000 --- a/stepper_motion/hardware_ini.h +++ /dev/null @@ -1,58 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/stepper_motion/ld/devices.data b/stepper_motion/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/stepper_motion/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/stepper_motion/ld/stm32f103x4.ld b/stepper_motion/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/stepper_motion/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103x6.ld b/stepper_motion/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/stepper_motion/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103x8.ld b/stepper_motion/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/stepper_motion/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xB.ld b/stepper_motion/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/stepper_motion/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xC.ld b/stepper_motion/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/stepper_motion/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xD.ld b/stepper_motion/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/stepper_motion/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xE.ld b/stepper_motion/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/stepper_motion/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xF.ld b/stepper_motion/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/stepper_motion/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/ld/stm32f103xG.ld b/stepper_motion/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/stepper_motion/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/stepper_motion/main.c b/stepper_motion/main.c deleted file mode 100644 index 509cadc..0000000 --- a/stepper_motion/main.c +++ /dev/null @@ -1,89 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "steppers.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - steppers_init(); - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - while(1){ - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - //check_and_parse_UART(USART1); // also check data in UART buffers - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/stepper_motion/main.h b/stepper_motion/main.h deleted file mode 100644 index 4de99af..0000000 --- a/stepper_motion/main.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -#endif // __MAIN_H__ - diff --git a/stepper_motion/steppers.c b/stepper_motion/steppers.c deleted file mode 100644 index 9c9f082..0000000 --- a/stepper_motion/steppers.c +++ /dev/null @@ -1,150 +0,0 @@ -/* - * steppers.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "steppers.h" -#include "user_proto.h" -#include - - -volatile int32_t Glob_steps = 0; -volatile int Dir = 0; // 0 - stop, 1 - move to +, -1 - move to - -int32_t stepper_period = STEPPER_DEFAULT_PERIOD; - -/** - * Init TIM2_CH3 (& remap to 5V tolerant PB10) [STEP] and PB11 [DIR] - */ -void steppers_init(){ - // Turn off JTAG & SWD, remap TIM2_CH3 to PB10 (five tolerant) - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP2); - // setup PB10 & PB11 - both opendrain - gpio_set_mode(GPIO_BANK_TIM2_PR2_CH3, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_ALTFN_OPENDRAIN, GPIO_TIM2_PR2_CH3); - // GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_PR2_CH3); - gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_OPENDRAIN, GPIO11); - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 36MHz of APB1 x2 = 72MHz - TIM2_PSC = STEPPER_TIM_DEFAULT_PRESCALER; // prescaler is (div - 1) - TIM2_CR1 = 0; - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_DIER = 0; - TIM2_SR = 0; // clear all flags - // PWM_OUT for TIM2_CH3 - TIM2_CCMR2 = TIM_CCMR2_CC3S_OUT | TIM_CCMR2_OC3M_PWM1; - // active is low - TIM2_CCER = TIM_CCER_CC3E | TIM_CCER_CC3P; - // enable update IRQ - TIM2_DIER = TIM_DIER_UIE; - TIM2_ARR = STEPPER_DEFAULT_PERIOD; - TIM2_CCR3 = STEPPER_PULSE_LEN; - nvic_enable_irq(NVIC_TIM2_IRQ); -} - -/** - * Set stepper period - */ -uint8_t set_stepper_speed(int32_t Period){ - if(Period > STEPPER_MIN_PERIOD && Period < STEPPER_MAX_PERIOD){ - P("Set stepper period to "); - if(Period > STEPPER_TIM_MAX_ARRVAL){ // redefine prescaler when value is too large - TIM2_PSC = STEPPER_TIM_HUNDR_PRESCALER; - Period /= 100; - print_int(Period*100); - TIM2_ARR = --Period; - }else{ // default prescaler - for 1MHz - print_int(Period); - TIM2_PSC = STEPPER_TIM_DEFAULT_PRESCALER; - TIM2_ARR = --Period; - } - stepper_period = Period; - newline(); - } - return 0; -} - -void stop_stepper(){ - TIM2_CCR3 = 0; - TIM2_CR1 = 0; - Glob_steps = 0; - Dir = 0; - gpio_set(GPIOB, GPIO11); // clear "direction" - P("Stopped!\n"); -} - -/** - * move stepper motor to N steps - * if motor is moving - just add Nsteps to current counter - */ -uint8_t move_stepper(int32_t Nsteps){ - int dir = 1; - if(!Nsteps) return 0; - if(TIM2_CR1){ // moving - if(!gpio_get(GPIOB, GPIO11)) dir = 0; // negative direction - Glob_steps += Nsteps; - if(Glob_steps < 0){ - Glob_steps = -Glob_steps; - dir = !dir; - } - }else{ // start timer if not moving - if(Nsteps < 0){ // change direction - dir = 0; - Nsteps = -Nsteps; - } - Glob_steps = Nsteps; - TIM2_ARR = stepper_period; - TIM2_CCR3 = STEPPER_PULSE_LEN; - TIM2_CR1 = TIM_CR1_CEN; - } - // set/clear direction - P("Rotate "); - if(dir){ - gpio_set(GPIOB, GPIO11); - }else{ - gpio_clear(GPIOB, GPIO11); - P("counter-"); - } - P("clockwise to "); - print_int(Glob_steps); - P(" steps\n"); - return 0; -} - -void tim2_isr(){ - // Next step - if(TIM2_SR & TIM_SR_UIF){ - if(--Glob_steps < 1){ // stop timer as steps ends - stop_stepper(); - } - } - TIM2_SR = 0; -} - - -int32_t stepper_get_period(){ - int32_t r = stepper_period + 1; - if(TIM2_PSC == STEPPER_TIM_DEFAULT_PRESCALER) return r; - else return r * 100; -} diff --git a/stepper_motion/steppers.h b/stepper_motion/steppers.h deleted file mode 100644 index cf701b7..0000000 --- a/stepper_motion/steppers.h +++ /dev/null @@ -1,50 +0,0 @@ -/* - * steppers.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ -#pragma once -#ifndef __STEPPERS_H__ -#define __STEPPERS_H__ - -#include "main.h" -// minimal period - 100us (10000ticks per second) -#define STEPPER_MIN_PERIOD (99) -// default period -#define STEPPER_DEFAULT_PERIOD (1299) -// high (off) pulse length: 70us (minimum value according documentation is 0.5us) -#define STEPPER_PULSE_LEN (69) -// TIM2 have 16bit ARR register, so max P with fixed prescaler is 65536 -#define STEPPER_TIM_MAX_ARRVAL (65536) -// max period allowed: 6553600us = 6.5s -#define STEPPER_MAX_PERIOD (6553601) -// default prescaler for 1MHz -#define STEPPER_TIM_DEFAULT_PRESCALER (71) -// prescaler for 100kHz -#define STEPPER_TIM_HUNDR_PRESCALER (7199) -void steppers_init(); - -uint8_t set_stepper_speed(int32_t Period); -uint8_t move_stepper(int32_t Nsteps); -void stop_stepper(); -extern volatile int32_t Glob_steps; -#define stepper_get_steps() (Glob_steps) - -extern int32_t stepper_period; -int32_t stepper_get_period(); -#endif // __STEPPERS_H__ diff --git a/stepper_motion/sync.c b/stepper_motion/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/stepper_motion/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/stepper_motion/sync.h b/stepper_motion/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/stepper_motion/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/stepper_motion/usb_cdc_simple.bin b/stepper_motion/usb_cdc_simple.bin deleted file mode 100755 index ef8526f..0000000 Binary files a/stepper_motion/usb_cdc_simple.bin and /dev/null differ diff --git a/stepper_motion/user_proto.c b/stepper_motion/user_proto.c deleted file mode 100644 index c4c9b52..0000000 --- a/stepper_motion/user_proto.c +++ /dev/null @@ -1,208 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "steppers.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("G\tgo to N steps\n"); - P("H\tshow this help\n"); - P("P\tset stepper period (us)\n"); - P("S\tstop motor\n"); - P("T\tshow current approx. time\n"); - P("W\tshow current steps value\n"); - P("X\tshow current stepper period\n"); -} - - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'G': - I = move_stepper; - READINT(); - break; - case 'H': // show help - help(); - break; - case 'P': - I = set_stepper_speed; - READINT(); - break; - case 'S': - stop_stepper(); - break; - case 'T': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case 'W': - print_int(stepper_get_steps()); - newline(); - break; - case 'X': - print_int(stepper_get_period()); - newline(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/stepper_motion/user_proto.h b/stepper_motion/user_proto.h deleted file mode 100644 index 69bf771..0000000 --- a/stepper_motion/user_proto.h +++ /dev/null @@ -1,47 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__ diff --git a/ultrasonic/Makefile b/ultrasonic/Makefile deleted file mode 100644 index 35b162d..0000000 --- a/ultrasonic/Makefile +++ /dev/null @@ -1,133 +0,0 @@ -BINARY = ultrasonic -BOOTPORT ?= /dev/ttyUSB0 -BOOTSPEED ?= 115200 -# change this linking script depending on particular MCU model, -# for example, if you have STM32F103VBT6, you should write: -LDSCRIPT = ld/stm32f103x8.ld -LIBNAME = opencm3_stm32f1 -DEFS = -DSTM32F1 -DEBUG - -OBJDIR = mk -INDEPENDENT_HEADERS= - -FP_FLAGS ?= -msoft-float -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 $(FP_FLAGS) -mfix-cortex-m3-ldrd - -############################################################################### -# Executables -PREFIX ?= arm-none-eabi - -RM := rm -f -RMDIR := rmdir -CC := $(PREFIX)-gcc -LD := $(PREFIX)-gcc -AR := $(PREFIX)-ar -AS := $(PREFIX)-as -OBJCOPY := $(PREFIX)-objcopy -OBJDUMP := $(PREFIX)-objdump -GDB := $(PREFIX)-gdb -STFLASH = $(shell which st-flash) -STBOOT = $(shell which stm32flash) - -############################################################################### -# Source files -LDSCRIPT ?= $(BINARY).ld -SRC = $(wildcard *.c) -OBJS = $(addprefix $(OBJDIR)/, $(SRC:%.c=%.o)) - -ifeq ($(strip $(OPENCM3_DIR)),) -OPENCM3_DIR := /usr/local/arm-none-eabi -$(info Using $(OPENCM3_DIR) path to library) -endif - -INCLUDE_DIR = $(OPENCM3_DIR)/include -LIB_DIR = $(OPENCM3_DIR)/lib -SCRIPT_DIR = $(OPENCM3_DIR)/scripts - -############################################################################### -# C flags -CFLAGS += -Os -g -CFLAGS += -Wall -Wextra -Wshadow -Wimplicit-function-declaration -CFLAGS += -Wredundant-decls -# -Wmissing-prototypes -Wstrict-prototypes -CFLAGS += -fno-common -ffunction-sections -fdata-sections - -############################################################################### -# C & C++ preprocessor common flags -CPPFLAGS += -MD -CPPFLAGS += -Wall -Werror -CPPFLAGS += -I$(INCLUDE_DIR) $(DEFS) - -############################################################################### -# Linker flags -LDFLAGS += --static -nostartfiles -LDFLAGS += -L$(LIB_DIR) -LDFLAGS += -T$(LDSCRIPT) -LDFLAGS += -Wl,-Map=$(*).map -LDFLAGS += -Wl,--gc-sections - -############################################################################### -# Used libraries -LDLIBS += -l$(LIBNAME) -LDLIBS += -Wl,--start-group -lc -lgcc -Wl,--end-group - -.SUFFIXES: .elf .bin .hex .srec .list .map .images -.SECONDEXPANSION: -.SECONDARY: - -ELF := $(OBJDIR)/$(BINARY).elf -LIST := $(OBJDIR)/$(BINARY).list -BIN := $(BINARY).bin -HEX := $(BINARY).hex - -all: bin - -elf: $(ELF) -bin: $(BIN) -hex: $(HEX) -list: $(LIST) - -$(OBJDIR): - mkdir $(OBJDIR) - -$(OBJDIR)/%.o: %.c - @printf " CC $<\n" - $(CC) $(CFLAGS) $(CPPFLAGS) $(ARCH_FLAGS) -o $@ -c $< - -$(SRC) : %.c : %.h $(INDEPENDENT_HEADERS) - @touch $@ - -%.h: ; - -$(BIN): $(ELF) - @printf " OBJCOPY $(BIN)\n" - $(OBJCOPY) -Obinary $(ELF) $(BIN) - -$(HEX): $(ELF) - @printf " OBJCOPY $(HEX)\n" - $(OBJCOPY) -Oihex $(ELF) $(HEX) - -$(LIST): $(ELF) - @printf " OBJDUMP $(LIST)\n" - $(OBJDUMP) -S $(ELF) > $(LIST) - -$(ELF): $(OBJDIR) $(OBJS) $(LDSCRIPT) $(LIB_DIR)/lib$(LIBNAME).a - @printf " LD $(ELF)\n" - $(LD) $(LDFLAGS) $(ARCH_FLAGS) $(OBJS) $(LDLIBS) -o $(ELF) - -clean: - @printf " CLEAN\n" - $(RM) $(OBJS) $(OBJDIR)/*.d $(ELF) $(HEX) $(LIST) $(OBJDIR)/*.map - $(RMDIR) $(OBJDIR) - -flash: $(BIN) - @printf " FLASH $(BIN)\n" - $(STFLASH) write $(BIN) 0x8000000 - -boot: $(BIN) - @printf " LOAD $(BIN) through bootloader\n" - $(STBOOT) -b$(BOOTSPEED) $(BOOTPORT) -w $(BIN) - -.PHONY: clean elf hex list flash boot - -#-include $(OBJS:.o=.d) diff --git a/ultrasonic/Readme.md b/ultrasonic/Readme.md deleted file mode 100644 index f9666de..0000000 --- a/ultrasonic/Readme.md +++ /dev/null @@ -1,6 +0,0 @@ -### Distance meter based on ultrasonic sensor HC-SR04 & Sharp 2Y0A02 IR sensor - -The same on STM8: [livejournal](http://eddy-em.livejournal.com/66122.html) (on russian), [github](https://sourceforge.net/p/stm8samples/code/ci/default/tree/distance_meter/). - -Allow not only to measure distance by ultrasonic distance-meter but also check transits -(Sharp sensor works at analog watchdog) \ No newline at end of file diff --git a/ultrasonic/cdcacm.c b/ultrasonic/cdcacm.c deleted file mode 100644 index 5f032ad..0000000 --- a/ultrasonic/cdcacm.c +++ /dev/null @@ -1,314 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2010 Gareth McMullin - * Copyright 2014 Edward V. Emelianov - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#include "cdcacm.h" -#include "user_proto.h" -#include "main.h" - -// Buffer for USB Tx -static uint8_t USB_Tx_Buffer[USB_TX_DATA_SIZE]; -static uint8_t USB_Tx_ptr = 0; -// connection flag -uint8_t USB_connected = 0; -static const struct usb_device_descriptor dev = { - .bLength = USB_DT_DEVICE_SIZE, - .bDescriptorType = USB_DT_DEVICE, - .bcdUSB = 0x0200, - .bDeviceClass = USB_CLASS_CDC, - .bDeviceSubClass = 0, - .bDeviceProtocol = 0, - .bMaxPacketSize0 = 64, - .idVendor = 0x0483, - .idProduct = 0x5740, - .bcdDevice = 0x0200, - .iManufacturer = 1, - .iProduct = 2, - .iSerialNumber = 3, - .bNumConfigurations = 1, -}; - -char usbdatabuf[USB_RX_DATA_SIZE]; // buffer for received data -int usbdatalen = 0; // lenght of received data - -/* - * This notification endpoint isn't implemented. According to CDC spec its - * optional, but its absence causes a NULL pointer dereference in Linux - * cdc_acm driver. - */ -static const struct usb_endpoint_descriptor comm_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x83, - .bmAttributes = USB_ENDPOINT_ATTR_INTERRUPT, - .wMaxPacketSize = 16, - .bInterval = 255, -}}; - -static const struct usb_endpoint_descriptor data_endp[] = {{ - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x01, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}, { - .bLength = USB_DT_ENDPOINT_SIZE, - .bDescriptorType = USB_DT_ENDPOINT, - .bEndpointAddress = 0x82, - .bmAttributes = USB_ENDPOINT_ATTR_BULK, - .wMaxPacketSize = 64, - .bInterval = 1, -}}; - -static const struct { - struct usb_cdc_header_descriptor header; - struct usb_cdc_call_management_descriptor call_mgmt; - struct usb_cdc_acm_descriptor acm; - struct usb_cdc_union_descriptor cdc_union; -} __attribute__((packed)) cdcacm_functional_descriptors = { - .header = { - .bFunctionLength = sizeof(struct usb_cdc_header_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_HEADER, - .bcdCDC = 0x0110, - }, - .call_mgmt = { - .bFunctionLength = - sizeof(struct usb_cdc_call_management_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_CALL_MANAGEMENT, - .bmCapabilities = 0, - .bDataInterface = 1, - }, - .acm = { - .bFunctionLength = sizeof(struct usb_cdc_acm_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_ACM, - .bmCapabilities = 0, - }, - .cdc_union = { - .bFunctionLength = sizeof(struct usb_cdc_union_descriptor), - .bDescriptorType = CS_INTERFACE, - .bDescriptorSubtype = USB_CDC_TYPE_UNION, - .bControlInterface = 0, - .bSubordinateInterface0 = 1, - }, -}; - -static const struct usb_interface_descriptor comm_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 0, - .bAlternateSetting = 0, - .bNumEndpoints = 1, - .bInterfaceClass = USB_CLASS_CDC, - .bInterfaceSubClass = USB_CDC_SUBCLASS_ACM, - .bInterfaceProtocol = USB_CDC_PROTOCOL_AT, - .iInterface = 0, - - .endpoint = comm_endp, - - .extra = &cdcacm_functional_descriptors, - .extralen = sizeof(cdcacm_functional_descriptors), -}}; - -static const struct usb_interface_descriptor data_iface[] = {{ - .bLength = USB_DT_INTERFACE_SIZE, - .bDescriptorType = USB_DT_INTERFACE, - .bInterfaceNumber = 1, - .bAlternateSetting = 0, - .bNumEndpoints = 2, - .bInterfaceClass = USB_CLASS_DATA, - .bInterfaceSubClass = 0, - .bInterfaceProtocol = 0, - .iInterface = 0, - - .endpoint = data_endp, -}}; - -static const struct usb_interface ifaces[] = {{ - .num_altsetting = 1, - .altsetting = comm_iface, -}, { - .num_altsetting = 1, - .altsetting = data_iface, -}}; - -static const struct usb_config_descriptor config = { - .bLength = USB_DT_CONFIGURATION_SIZE, - .bDescriptorType = USB_DT_CONFIGURATION, - .wTotalLength = 0, - .bNumInterfaces = 2, - .bConfigurationValue = 1, - .iConfiguration = 0, - .bmAttributes = 0x80, - .bMaxPower = 0x32, - - .interface = ifaces, -}; - -static const char *usb_strings[] = { - "Organisation, author", - "device", - "version", -}; - -// default line coding: B115200, 1stop, 8bits, parity none -struct usb_cdc_line_coding linecoding = { - .dwDTERate = 115200, - .bCharFormat = USB_CDC_1_STOP_BITS, - .bParityType = USB_CDC_NO_PARITY, - .bDataBits = 8, -}; - -/* Buffer to be used for control requests. */ -uint8_t usbd_control_buffer[128]; - -/** - * This function runs every time it gets a request for control parameters get/set - * parameter SET_LINE_CODING used to change USART1 parameters: if you want to - * change them, just connect through USB with required parameters - */ -static int cdcacm_control_request(usbd_device *usbd_dev, struct usb_setup_data *req, uint8_t **buf, - uint16_t *len, void (**complete)(usbd_device *usbd_dev, struct usb_setup_data *req)){ - (void)complete; - (void)buf; - (void)usbd_dev; - char local_buf[10]; - struct usb_cdc_line_coding lc; - - switch (req->bRequest) { - case SET_CONTROL_LINE_STATE:{ - if(req->wValue){ // terminal is opened - USB_connected = 1; - }else{ // terminal is closed - USB_connected = 0; - } - /* - * This Linux cdc_acm driver requires this to be implemented - * even though it's optional in the CDC spec, and we don't - * advertise it in the ACM functional descriptor. - */ - struct usb_cdc_notification *notif = (void *)local_buf; - /* We echo signals back to host as notification. */ - notif->bmRequestType = 0xA1; - notif->bNotification = USB_CDC_NOTIFY_SERIAL_STATE; - notif->wValue = 0; - notif->wIndex = 0; - notif->wLength = 2; - local_buf[8] = req->wValue & 3; - local_buf[9] = 0; - usbd_ep_write_packet(usbd_dev, 0x83, local_buf, 10); - }break; - case SET_LINE_CODING: - if (!len || (*len != sizeof(struct usb_cdc_line_coding))) - return 0; - memcpy((void *)&lc, (void *)*buf, *len); - // Mark & Space parity don't support by hardware, check it - if(lc.bParityType == USB_CDC_MARK_PARITY || lc.bParityType == USB_CDC_SPACE_PARITY){ - return 0; // error - }else{ -// memcpy((void *)&linecoding, (void *)&lc, sizeof(struct usb_cdc_line_coding)); -// UART_setspeed(USART1, &linecoding); - } - break; - case GET_LINE_CODING: // return linecoding buffer - if(len && *len == sizeof(struct usb_cdc_line_coding)) - memcpy((void *)*buf, (void *)&linecoding, sizeof(struct usb_cdc_line_coding)); - //usbd_ep_write_packet(usbd_dev, 0x83, (char*)&linecoding, sizeof(linecoding)); - break; - default: - return 0; - } - return 1; -} - -static void cdcacm_data_rx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - int len = usbd_ep_read_packet(usbd_dev, 0x01, usbdatabuf + usbdatalen, USB_RX_DATA_SIZE - usbdatalen); - usbdatalen += len; - if(usbdatalen >= USB_RX_DATA_SIZE){ // buffer overflow - drop all its contents - usbdatalen = 0; - } -} - -static void cdcacm_data_tx_cb(usbd_device *usbd_dev, uint8_t ep){ - (void)ep; - (void)usbd_dev; - - usb_send_buffer(); -} - -static void cdcacm_set_config(usbd_device *usbd_dev, uint16_t wValue) -{ - (void)wValue; - (void)usbd_dev; - - usbd_ep_setup(usbd_dev, 0x01, USB_ENDPOINT_ATTR_BULK, USB_RX_DATA_SIZE, cdcacm_data_rx_cb); - usbd_ep_setup(usbd_dev, 0x82, USB_ENDPOINT_ATTR_BULK, USB_TX_DATA_SIZE, cdcacm_data_tx_cb); - usbd_ep_setup(usbd_dev, 0x83, USB_ENDPOINT_ATTR_INTERRUPT, 16, NULL); - - usbd_register_control_callback( - usbd_dev, - USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE, - USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT, - cdcacm_control_request); -} - -static usbd_device *current_usb = NULL; - -usbd_device *USB_init(){ - current_usb = usbd_init(&stm32f103_usb_driver, &dev, &config, - usb_strings, 3, usbd_control_buffer, sizeof(usbd_control_buffer)); - if(!current_usb) return NULL; - usbd_register_set_config_callback(current_usb, cdcacm_set_config); - return current_usb; -} - -mutex_t send_block_mutex = MUTEX_UNLOCKED; -/** - * Put byte into USB buffer to send - * @param byte - a byte to put into a buffer - */ -void usb_send(uint8_t byte){ - mutex_lock(&send_block_mutex); - USB_Tx_Buffer[USB_Tx_ptr++] = byte; - mutex_unlock(&send_block_mutex); - if(USB_Tx_ptr == USB_TX_DATA_SIZE){ // buffer can be overflowed - send it! - usb_send_buffer(); - } -} - -/** - * Send all data in buffer over USB - * this function runs when buffer is full or on SysTick - */ -void usb_send_buffer(){ - if(MUTEX_LOCKED == mutex_trylock(&send_block_mutex)) return; - if(USB_Tx_ptr){ - if(current_usb && USB_connected){ - // usbd_ep_write_packet return 0 if previous packet isn't transmit yet - while(USB_Tx_ptr != usbd_ep_write_packet(current_usb, 0x82, USB_Tx_Buffer, USB_Tx_ptr)); - usbd_poll(current_usb); - } - USB_Tx_ptr = 0; - } - mutex_unlock(&send_block_mutex); -} diff --git a/ultrasonic/cdcacm.h b/ultrasonic/cdcacm.h deleted file mode 100644 index 1051d83..0000000 --- a/ultrasonic/cdcacm.h +++ /dev/null @@ -1,54 +0,0 @@ -/* - * ccdcacm.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __CCDCACM_H__ -#define __CCDCACM_H__ - -#include - -// commands through EP0 -#define SEND_ENCAPSULATED_COMMAND 0x00 -#define GET_ENCAPSULATED_RESPONSE 0x01 -#define SET_COMM_FEATURE 0x02 -#define GET_COMM_FEATURE 0x03 -#define CLEAR_COMM_FEATURE 0x04 -#define SET_LINE_CODING 0x20 -#define GET_LINE_CODING 0x21 -#define SET_CONTROL_LINE_STATE 0x22 -#define SEND_BREAK 0x23 - -// Size of input/output buffers -#define USB_TX_DATA_SIZE 64 -#define USB_RX_DATA_SIZE 64 - -// USB connection flag -extern uint8_t USB_connected; -extern struct usb_cdc_line_coding linecoding; - -extern char usbdatabuf[]; -extern int usbdatalen; - -usbd_device *USB_init(); -void usb_send(uint8_t byte); -void usb_send_buffer(); - -#endif // __CCDCACM_H__ diff --git a/ultrasonic/hardware_ini.c b/ultrasonic/hardware_ini.c deleted file mode 100644 index 717ab14..0000000 --- a/ultrasonic/hardware_ini.c +++ /dev/null @@ -1,57 +0,0 @@ -/* - * hardware_ini.c - functions for HW initialisation - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -/* - * All hardware-dependent initialisation & definition should be placed here - * and in hardware_ini.h - * - */ - -#include "main.h" -#include "hardware_ini.h" - -/** - * GPIO initialisaion: clocking + pins setup - */ -void GPIO_init(){ - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN | - RCC_APB2ENR_IOPBEN | RCC_APB2ENR_IOPCEN | RCC_APB2ENR_IOPDEN | - RCC_APB2ENR_IOPEEN); -/* - // USB_DISC: push-pull - gpio_set_mode(USB_DISC_PORT, GPIO_MODE_OUTPUT_2_MHZ, - GPIO_CNF_OUTPUT_PUSHPULL, USB_DISC_PIN); - // USB_POWER: open drain, externall pull down with R7 (22k) - gpio_set_mode(USB_POWER_PORT, GPIO_MODE_INPUT, - GPIO_CNF_INPUT_FLOAT, USB_POWER_PIN); -*/ -} - -/* - * SysTick used for system timer with period of 1ms - */ -void SysTick_init(){ - systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8); // Systyck: 72/8=9MHz - systick_set_reload(8999); // 9000 pulses: 1kHz - systick_interrupt_enable(); - systick_counter_enable(); -} - diff --git a/ultrasonic/hardware_ini.h b/ultrasonic/hardware_ini.h deleted file mode 100644 index 11fe628..0000000 --- a/ultrasonic/hardware_ini.h +++ /dev/null @@ -1,60 +0,0 @@ -/* - * hardware_ini.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __HARDWARE_INI_H__ -#define __HARDWARE_INI_H__ - -#include "ultrasonic.h" - -/* - * Timers: - * SysTick - system time - */ - - -void GPIO_init(); -void SysTick_init(); - -/* - * USB interface - * connect boot1 jumper to gnd, boot0 to gnd; and reconnect boot0 to +3.3 to boot flash - */ -/* -// USB_DICS (disconnect) - PC11 -#define USB_DISC_PIN GPIO11 -#define USB_DISC_PORT GPIOC -// USB_POWER (high level when USB connected to PC) -#define USB_POWER_PIN GPIO10 -#define USB_POWER_PORT GPIOC -// change signal level on USB diconnect pin -#define usb_disc_high() gpio_set(USB_DISC_PORT, USB_DISC_PIN) -#define usb_disc_low() gpio_clear(USB_DISC_PORT, USB_DISC_PIN) -// in case of n-channel FET on 1.5k pull-up change on/off disconnect means low level -// in case of pnp bipolar transistor or p-channel FET on 1.5k pull-up disconnect means high level -#define usb_disconnect() usb_disc_high() -#define usb_connect() usb_disc_low() -*/ -// my simple devboard have no variants for programmed connection/disconnection of USB -#define usb_disconnect() -#define usb_connect() - -#endif // __HARDWARE_INI_H__ diff --git a/ultrasonic/ld/devices.data b/ultrasonic/ld/devices.data deleted file mode 100644 index 7f29538..0000000 --- a/ultrasonic/ld/devices.data +++ /dev/null @@ -1,9 +0,0 @@ -stm32f103?4* stm32f1 ROM=16K RAM=6K -stm32f103?6* stm32f1 ROM=32K RAM=10K -stm32f103?8* stm32f1 ROM=64K RAM=20K -stm32f103?b* stm32f1 ROM=128K RAM=20K -stm32f103?c* stm32f1 ROM=256K RAM=48K -stm32f103?d* stm32f1 ROM=384K RAM=64K -stm32f103?e* stm32f1 ROM=512K RAM=64K -stm32f103?f* stm32f1 ROM=768K RAM=96K -stm32f103?g* stm32f1 ROM=1024K RAM=96K diff --git a/ultrasonic/ld/stm32f103x4.ld b/ultrasonic/ld/stm32f103x4.ld deleted file mode 100644 index efed65e..0000000 --- a/ultrasonic/ld/stm32f103x4.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 6K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103x6.ld b/ultrasonic/ld/stm32f103x6.ld deleted file mode 100644 index 13f05f9..0000000 --- a/ultrasonic/ld/stm32f103x6.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 32K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103x8.ld b/ultrasonic/ld/stm32f103x8.ld deleted file mode 100644 index 2c4640f..0000000 --- a/ultrasonic/ld/stm32f103x8.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xB.ld b/ultrasonic/ld/stm32f103xB.ld deleted file mode 100644 index 138444d..0000000 --- a/ultrasonic/ld/stm32f103xB.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xC.ld b/ultrasonic/ld/stm32f103xC.ld deleted file mode 100644 index fda76bf..0000000 --- a/ultrasonic/ld/stm32f103xC.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 256K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 48K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xD.ld b/ultrasonic/ld/stm32f103xD.ld deleted file mode 100644 index 0f996c2..0000000 --- a/ultrasonic/ld/stm32f103xD.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 384K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xE.ld b/ultrasonic/ld/stm32f103xE.ld deleted file mode 100644 index b0fcb69..0000000 --- a/ultrasonic/ld/stm32f103xE.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xF.ld b/ultrasonic/ld/stm32f103xF.ld deleted file mode 100644 index 62d47db..0000000 --- a/ultrasonic/ld/stm32f103xF.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 768K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/ld/stm32f103xG.ld b/ultrasonic/ld/stm32f103xG.ld deleted file mode 100644 index 0c0c968..0000000 --- a/ultrasonic/ld/stm32f103xG.ld +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Karl Palsson - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* Linker script for STM32F100x4, 16K flash, 4K RAM. */ - -/* Define memory regions. */ -MEMORY -{ - rom (rx) : ORIGIN = 0x08000000, LENGTH = 1024K - ram (rwx) : ORIGIN = 0x20000000, LENGTH = 96K -} - -/* Include the common ld script. */ -INCLUDE libopencm3_stm32f1.ld - diff --git a/ultrasonic/main.c b/ultrasonic/main.c deleted file mode 100644 index f4c1d7a..0000000 --- a/ultrasonic/main.c +++ /dev/null @@ -1,120 +0,0 @@ -/* - * main.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "main.h" -#include "hardware_ini.h" -#include "cdcacm.h" -#include "sharp.h" - -volatile uint32_t Timer = 0; // global timer (milliseconds) -usbd_device *usbd_dev; - -int main(){ - uint32_t Old_timer = 0; - - // RCC clocking: 8MHz oscillator -> 72MHz system - rcc_clock_setup_in_hse_8mhz_out_72mhz(); - - GPIO_init(); - - usb_disconnect(); // turn off USB while initializing all - - // USB - usbd_dev = USB_init(); - - // SysTick is a system timer with 1ms period - SysTick_init(); - tim2_init(); - //init_sharp_sensor(); - - // wait a little and then turn on USB pullup -// for (i = 0; i < 0x800000; i++) -// __asm__("nop"); - - usb_connect(); // turn on USB - - uint32_t oldL = 0; - while(1){ - uint32_t L; - usbd_poll(usbd_dev); - if(usbdatalen){ // there's something in USB buffer - usbdatalen = parse_incoming_buf(usbdatabuf, usbdatalen); - } - if(AWD_flag){ - P("Int, value = "); - print_int(AWD_value); - P(" ADU\n"); - AWD_flag = 0; - } - if(ultrasonic_get(&L)){ - if(!cont){ - P("Measured length: "); - print_int(L); - P("mm\n"); - oldL = 0; - }else{ - if(!oldL){ - oldL = L; - }else{ - uint32_t diff = (oldL > L) ? oldL - L : L - oldL; - if(diff > MAX_LEN_DIFF){ - P("Pass! Was: "); - print_int(oldL); - P(", become: "); - print_int(L); - P("!!!\n"); - oldL = L; - } - } - start_ultrasonic(); - } - } - if(Timer - Old_timer > 999){ // one-second cycle - Old_timer += 1000; - }else if(Timer < Old_timer){ // Timer overflow - Old_timer = 0; - } - } -} - - -/** - * SysTick interrupt: increment global time & send data buffer through USB - */ -void sys_tick_handler(){ - Timer++; - usbd_poll(usbd_dev); - usb_send_buffer(); -} - -// pause function, delay in ms -void Delay(uint16_t _U_ time){ - uint32_t waitto = Timer + time; - while(Timer < waitto); -} - -/** - * print current time in milliseconds: 4 bytes for ovrvlow + 4 bytes for time - * with ' ' as delimeter - */ -void print_time(){ - print_int(Timer); -} diff --git a/ultrasonic/main.h b/ultrasonic/main.h deleted file mode 100644 index 5dcdafb..0000000 --- a/ultrasonic/main.h +++ /dev/null @@ -1,57 +0,0 @@ -/* - * main.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - - -#pragma once -#ifndef __MAIN_H__ -#define __MAIN_H__ - -#include -#include // memcpy -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#define ADC_CHANNELS_NUMBER (10) - -#include "sync.h" // mutexes -#include "user_proto.h" - -#define _U_ __attribute__((__unused__)) -#define U8(x) ((uint8_t) x) -#define U16(x) ((uint16_t) x) -#define U32(x) ((uint32_t) x) - -extern volatile uint32_t Timer; // global timer (milliseconds) -void Delay(uint16_t time); - -// max diff in continuous measurements - 100mm -#define MAX_LEN_DIFF (100) - -#endif // __MAIN_H__ - diff --git a/ultrasonic/sharp.c b/ultrasonic/sharp.c deleted file mode 100644 index f081aa8..0000000 --- a/ultrasonic/sharp.c +++ /dev/null @@ -1,72 +0,0 @@ -/* - * sharp.c - functions for Sharp 2Y0A02 distance meter - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "sharp.h" -#include "main.h" - -int AWD_flag = 0; -uint16_t AWD_value = 0; - -void init_sharp_sensor(){ - // Make sure the ADC doesn't run during config - adc_off(ADC1); - // enable ADC & PA0 clocking - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_ADC1EN | RCC_APB2ENR_IOPAEN); - rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV4); - gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0); - // set sample time: 239.5 cycles for better results - ADC1_SMPR2 = 7; - // continuous conv, enable - ADC1_CR2 = ADC_CR2_CONT | ADC_CR2_ADON; - // reset calibration registers & start calibration - ADC1_CR2 |= ADC_CR2_RSTCAL; - while(ADC1_CR2 & ADC_CR2_RSTCAL); // wait for registers reset - ADC1_CR2 |= ADC_CR2_CAL; - while(ADC1_CR2 & ADC_CR2_CAL); // wait for calibration ends - // set threshold limits - ADC1_HTR = ADC_WDG_HIGH; - ADC1_LTR = ADC_WDG_LOW; - // enable analog watchdog on single regular channel 0 & enable interrupt - ADC1_CR1 = ADC_CR1_AWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDIE; - nvic_enable_irq(NVIC_ADC1_2_IRQ); - ADC1_CR2 |= ADC_CR2_SWSTART; - // start - to do it we need set ADC_CR2_ADON again! - ADC1_CR2 |= ADC_CR2_ADON; - DBG("ADC started\n"); -} - -void adc1_2_isr(){ - AWD_value = ADC1_DR; - if(ADC1_SR & ADC_SR_AWD){ // analog watchdog event - AWD_flag = 1; - // ADC1_CR1 &= ~(ADC_CR1_AWDIE | ADC_CR1_AWDEN); - // nvic_disable_irq(NVIC_ADC1_2_IRQ); - if(AWD_value >= ADC_WDG_HIGH){ // high threshold - ADC1_HTR = 0x0fff; // remove high threshold, only wait for LOW - ADC1_LTR = ADC_WDG_LOW; - }else{ - ADC1_HTR = ADC_WDG_HIGH; - ADC1_LTR = 0; - } - //ADC1_CR1 |= ADC_CR1_AWDIE; - } - ADC1_SR = 0; -} diff --git a/ultrasonic/sharp.h b/ultrasonic/sharp.h deleted file mode 100644 index c2d48bb..0000000 --- a/ultrasonic/sharp.h +++ /dev/null @@ -1,38 +0,0 @@ -/* - * sharp.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __SHARP_H__ -#define __SHARP_H__ - -#include - -extern int AWD_flag; -extern uint16_t AWD_value; - -// > 2.5V - something nearest 1m -#define ADC_WDG_HIGH ((uint16_t)3000) -// < 0.6V - nothing in front of sensor -#define ADC_WDG_LOW ((uint16_t)750) - -void init_sharp_sensor(); - -#endif // __SHARP_H__ diff --git a/ultrasonic/sync.c b/ultrasonic/sync.c deleted file mode 100644 index ba688c3..0000000 --- a/ultrasonic/sync.c +++ /dev/null @@ -1,93 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -/* - * TODO: - * implement mutexes for other type of MCU (which doesn't have strex & ldrex) - */ - -#include - -/* DMB is supported on CM0 */ -void __dmb() -{ - __asm__ volatile ("dmb"); -} - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("ldrex %0, [%1]" : "=r" (res) : "r" (addr)); - return res; -} - -uint32_t __strex(uint32_t val, volatile uint32_t *addr) -{ - uint32_t res; - __asm__ volatile ("strex %0, %2, [%1]" - : "=&r" (res) : "r" (addr), "r" (val)); - return res; -} - -void mutex_lock(mutex_t *m) -{ - uint32_t status = 0; - - do { - /* Wait until the mutex is unlocked. */ - while (__ldrex(m) != MUTEX_UNLOCKED); - - /* Try to acquire it. */ - status = __strex(MUTEX_LOCKED, m); - - /* Did we get it? If not then try again. */ - } while (status != 0); - - /* Execute the mysterious Data Memory Barrier instruction! */ - __dmb(); -} - -void mutex_unlock(mutex_t *m) -{ - /* Ensure accesses to protected resource are finished */ - __dmb(); - - /* Free the lock. */ - *m = MUTEX_UNLOCKED; -} - -/* - * Try to lock mutex - * if it's already locked or there was error in STREX, return MUTEX_LOCKED - * else return MUTEX_UNLOCKED - */ -mutex_t mutex_trylock(mutex_t *m){ - uint32_t status = 0; - mutex_t old_lock = __ldrex(m); // get mutex value - // set mutex - status = __strex(MUTEX_LOCKED, m); - if(status == 0) __dmb(); - else old_lock = MUTEX_LOCKED; - return old_lock; -} - -#endif diff --git a/ultrasonic/sync.h b/ultrasonic/sync.h deleted file mode 100644 index bfe837b..0000000 --- a/ultrasonic/sync.h +++ /dev/null @@ -1,53 +0,0 @@ -/* - * This file is part of the libopencm3 project. - * - * Copyright (C) 2012 Fergus Noble - * - * This library is free software: you can redistribute it and/or modify - * it under the terms of the GNU Lesser General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This library 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 Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public License - * along with this library. If not, see . - */ - -#ifndef LIBOPENCM3_CM3_SYNC_H -#define LIBOPENCM3_CM3_SYNC_H - -void __dmb(void); - -/* Implements synchronisation primitives as discussed in the ARM document - * DHT0008A (ID081709) "ARM Synchronization Primitives" and the ARM v7-M - * Architecture Reference Manual. -*/ - -/* --- Exclusive load and store instructions ------------------------------- */ - -/* Those are defined only on CM3 or CM4 */ -#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) - -uint32_t __ldrex(volatile uint32_t *addr); -uint32_t __strex(uint32_t val, volatile uint32_t *addr); - -/* --- Convenience functions ----------------------------------------------- */ - -/* Here we implement some simple synchronisation primitives. */ - -typedef uint32_t mutex_t; - -#define MUTEX_UNLOCKED 0 -#define MUTEX_LOCKED 1 - -void mutex_lock(mutex_t *m); -void mutex_unlock(mutex_t *m); -mutex_t mutex_trylock(mutex_t *m); - -#endif - -#endif diff --git a/ultrasonic/ultrasonic.bin b/ultrasonic/ultrasonic.bin deleted file mode 100755 index 305d3b2..0000000 Binary files a/ultrasonic/ultrasonic.bin and /dev/null differ diff --git a/ultrasonic/ultrasonic.c b/ultrasonic/ultrasonic.c deleted file mode 100644 index 41d010c..0000000 --- a/ultrasonic/ultrasonic.c +++ /dev/null @@ -1,165 +0,0 @@ -/* - * ultrasonic.c - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include -#include -#include -#include - -#include "ultrasonic.h" -#include "user_proto.h" - -static usmode US_mode = US_MODE_OFF; -static int overcapture = 0; - -#ifndef TIM_CCMR2_CC3S_IN_TI4 -#define TIM_CCMR2_CC3S_IN_TI4 (2) -#endif -#ifndef TIM_CCMR2_CC4S_IN_TI4 -#define TIM_CCMR2_CC4S_IN_TI4 (1 << 8) -#endif -/** - * Init timer 2 (&remap channels 3&4 to five-tolerant ports) - */ -void tim2_init(){ - // Turn off JTAG & SWD, remap TIM2_CH3/TIM2_CH4 to PB10/PB11 (five tolerant) - // don't forget about AFIO clock & PB clock! - rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_AFIOEN | RCC_APB2ENR_IOPBEN); - gpio_primary_remap(AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF, AFIO_MAPR_TIM2_REMAP_PARTIAL_REMAP2); - // setup PB10 & PB11 - // PB10 - Trig output - push/pull - gpio_set_mode(GPIO_BANK_TIM2_PR2_CH3, GPIO_MODE_OUTPUT_10_MHZ, - GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_PR2_CH3); -// gpio_set_mode(GPIO_BANK_TIM2_CH3, GPIO_MODE_OUTPUT_10_MHZ, -// GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO_TIM2_CH3); - // PB11 - Echo input - floating -// gpio_set_mode(GPIO_BANK_TIM2_PR2_CH4, GPIO_MODE_INPUT, -// GPIO_CNF_INPUT_FLOAT, GPIO_TIM2_PR2_CH4); - rcc_periph_clock_enable(RCC_TIM2); - timer_reset(TIM2); - // timers have frequency of 1MHz -- 1us for one step - // 36MHz of APB1 - timer_set_mode(TIM2, TIM_CR1_CKD_CK_INT, TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP); - // 72MHz div 72 = 1MHz - TIM2_PSC = 71; // prescaler is (div - 1) - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; -// DBG("Timer configured\n"); -} - -/** - * Send Trig signal - * return 0 if another measurement still in process - */ -int start_ultrasonic(){ - if(US_mode != US_MODE_OFF && US_mode != US_MODE_READY) return 0; - overcapture = 0; - TIM2_CR1 = 0; - //TIM2_CR1 = TIM_CR1_URS; // Turn off timer to reconfigure, dusable UEV by UG set - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - TIM2_DIER = 0; - TIM2_SR = 0; // clear all flags - TIM2_ARR = TRIG_T; - TIM2_CCR3 = TRIG_L; - // PWM_OUT for TIM2_CH3 - TIM2_CCMR2 = TIM_CCMR2_CC3S_OUT | TIM_CCMR2_OC3M_PWM1; - // start measurement, active is high - TIM2_CCER = TIM_CCER_CC3E; - // enable CC3 IRQ - TIM2_DIER = TIM_DIER_CC3IE; - nvic_enable_irq(NVIC_TIM2_IRQ); - US_mode = US_MODE_TRIG; - // start timer in one-pulse mode without update event - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN | TIM_CR1_UDIS; - return 1; -} - -/** - * Start measurement: - * TIM2_CH3 will capture high level & TIM2_CH4 will capture low - * The timer configured to 65536us to detect signal lost - */ -inline void run_measrmnt(){ - US_mode = US_MODE_WAIT; - TIM2_CR1 = 0; // Turn off timer to reconfigure - TIM2_DIER = 0; - TIM2_CCER = 0; - TIM2_CCMR2 = 0; - //DBG("triggered\n"); - TIM2_SR = 0; // clear all flags - TIM2_ARR = MAX_MSRMNT_LEN; - // TIM2_CH3 & TIM2_CH4 configured as inputs, TIM2_CH3 connected to CH4 - TIM2_CCMR2 = TIM_CCMR2_CC3S_IN_TI4 | TIM_CCMR2_CC4S_IN_TI4; - // start - TIM2_CCER = TIM_CCER_CC4P | TIM_CCER_CC4E | TIM_CCER_CC3E; - // enable interrupts CH3, CH4 & update - TIM2_DIER = TIM_DIER_CC3IE | TIM_DIER_CC4IE | TIM_DIER_UIE; - // start timer in one-pulse mode - TIM2_CR1 = TIM_CR1_OPM | TIM_CR1_CEN; -} - -void tim2_isr(){ - // No signal - if(TIM2_SR & TIM_SR_UIF){ // update interrupt - TIM2_SR = 0; - overcapture = 1; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - US_mode = US_MODE_READY; - DBG("overcaptured\n"); - } - // end of Trig pulse or start of measurements - if(TIM2_SR & TIM_SR_CC3IF){ // CCR ch3 interrupt - if(US_mode == US_MODE_TRIG){ // triggered - run measurement - run_measrmnt(); - }else if(US_mode == US_MODE_WAIT){ - US_mode = US_MODE_MEASUREMENT; - } - TIM2_SR &= ~TIM_SR_CC3IF; - } - if(TIM2_SR & TIM_SR_CC4IF){ - if(US_mode == US_MODE_MEASUREMENT){ - US_mode = US_MODE_READY; - nvic_disable_irq(NVIC_TIM2_IRQ); - TIM2_DIER = 0; - TIM2_CR1 = 0; // turn off timer - we don't need it more - } - TIM2_SR &= ~TIM_SR_CC3IF; - } -} - -/** - * Measure distance - * return 1 if measurements done - * set L to distance (in mm) or 0 in case of overcapture (no signal) - */ -int ultrasonic_get(uint32_t *L){ - uint32_t D; - if(US_mode != US_MODE_READY) - return 0; - US_mode = US_MODE_OFF; - if(!overcapture){ - D = ((uint32_t)(TIM2_CCR4 - TIM2_CCR3)) * 170; - *L = D / 1000; - }else *L = 0; - return 1; -} diff --git a/ultrasonic/ultrasonic.geany b/ultrasonic/ultrasonic.geany deleted file mode 100644 index d29cb53..0000000 --- a/ultrasonic/ultrasonic.geany +++ /dev/null @@ -1,52 +0,0 @@ -[file_prefs] -final_new_line=true -ensure_convert_new_lines=true -strip_trailing_spaces=true -replace_tabs=false - -[indentation] -indent_width=4 -indent_type=1 -indent_hard_tab_width=4 -detect_indent=false -detect_indent_width=false -indent_mode=3 - -[project] -name=ultrasonic -base_path=/home/eddy/Docs/SAO/ELECTRONICS/STM32/c8t6/ultrasonic/ -description= - -[long line marker] -long_line_behaviour=1 -long_line_column=80 - -[files] -current_page=8 -FILE_NAME_0=4955;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fultrasonic.c;0;4 -FILE_NAME_1=1405;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fultrasonic.h;0;4 -FILE_NAME_2=1366;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fuser_proto.c;0;4 -FILE_NAME_3=1108;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fuser_proto.h;0;4 -FILE_NAME_4=1778;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fmain.c;0;4 -FILE_NAME_5=1205;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fmain.h;0;4 -FILE_NAME_6=1157;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fhardware_ini.c;0;4 -FILE_NAME_7=925;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fhardware_ini.h;0;4 -FILE_NAME_8=870;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fsharp.c;0;4 -FILE_NAME_9=909;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fc8t6%2Fultrasonic%2Fsharp.h;0;4 -FILE_NAME_10=0;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Ff1%2Ftimer.h;0;4 -FILE_NAME_11=9634;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Fcommon%2Ftimer_common_all.h;0;4 -FILE_NAME_12=0;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Fcommon%2Fgpio_common_all.h;0;4 -FILE_NAME_13=28941;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Ff1%2Fgpio.h;0;4 -FILE_NAME_14=0;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Flib%2Fstm32%2Ff1%2Fgpio.c;0;4 -FILE_NAME_15=1639;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Ff1%2Fadc.h;0;4 -FILE_NAME_16=11790;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Fcommon%2Fadc_common_v1.h;0;4 -FILE_NAME_17=22482;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Flib%2Fstm32%2Fcommon%2Fadc_common_v1.c;0;4 -FILE_NAME_18=4646;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Flib%2Fstm32%2Ff1%2Fadc.c;0;4 -FILE_NAME_19=9093;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2FWORK%2FIR-controller%2Fwith_opencm3%2Fhardware_ini.c;0;4 -FILE_NAME_20=3059;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencm3%2Fstm32%2Ff1%2Fnvic.h;0;4 -FILE_NAME_21=0;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Flib%2Fstm32%2Ff1%2Frcc.c;0;4 -FILE_NAME_22=4504;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Flib%2Fstm32%2Fcommon%2Frcc_common_all.c;0;4 -FILE_NAME_23=2498;C;0;EUTF-8;1;1;0;%2Fhome%2Feddy%2FDocs%2FSAO%2FELECTRONICS%2FSTM32%2Fopenstm32%2Flibopencm3%2Finclude%2Flibopencmsis%2Fcore_cm3.h;0;4 - -[VTE] -last_dir=/home/eddy/Docs/SAO/Cameras/FLI_camera/my/Mytakepic diff --git a/ultrasonic/ultrasonic.h b/ultrasonic/ultrasonic.h deleted file mode 100644 index 86432dc..0000000 --- a/ultrasonic/ultrasonic.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * ultrasonic.h - * - * Copyright 2015 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __ULTRASONIC_H__ -#define __ULTRASONIC_H__ - -#include - -void tim2_init(); -int start_ultrasonic(); -int ultrasonic_get(uint32_t *L); - - -// Sensor mode -typedef enum{ - US_MODE_OFF // sensor is off - ,US_MODE_TRIG // sensor triggered - ,US_MODE_WAIT // wait for pulse - ,US_MODE_MEASUREMENT // measurement in process - ,US_MODE_READY // measurements done -} usmode; - -// trigger time: after trigger event ends, timer will be configured for capture - 20us -#define TRIG_T (200) -// trigger length - 10us -#define TRIG_L (10) -// max length of measurement (to detect signal absence) -#define MAX_MSRMNT_LEN (65535) - -#endif // __ULTRASONIC_H__ diff --git a/ultrasonic/user_proto.c b/ultrasonic/user_proto.c deleted file mode 100644 index 8e7f3f0..0000000 --- a/ultrasonic/user_proto.c +++ /dev/null @@ -1,213 +0,0 @@ -/* - * user_proto.c - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#include "cdcacm.h" -#include "main.h" -#include "hardware_ini.h" -#include "sharp.h" - -// integer value given by user -static volatile int32_t User_value = 0; -enum{ - UVAL_START, // user start to write integer value - UVAL_ENTERED, // value entered but not printed - UVAL_BAD // entered bad value -}; -uint8_t Uval_ready = UVAL_BAD, cont = 0; - -int read_int(char *buf, int cnt); - -intfun I = NULL; // function to process entered integer - -#define READINT() do{i += read_int(&buf[i+1], len-i-1);}while(0) - -void help(){ - P("A\tshow ADC value\n"); - P("H\tshow this help\n"); - P("D\tmeasure distance\n"); - P("I\tinit sharp\n"); - P("T\tshow timer value\n"); - P("S\tstart/stop continuous measurement\n"); -} - -/** - * show entered integer value - */ -uint8_t show_int(int32_t v){ - newline(); - print_int(v); - newline(); - return 0; -} - -/** - * parse command buffer buf with length len - * return 0 if buffer processed or len if there's not enough data in buffer - */ -int parse_incoming_buf(char *buf, int len){ - uint8_t command; - //uint32_t utmp; - int i = 0; - if(Uval_ready == UVAL_START){ // we are in process of user's value reading - i += read_int(buf, len); - } - if(Uval_ready == UVAL_ENTERED){ - //print_int(User_value); // printout readed integer value for error control - Uval_ready = UVAL_BAD; // clear Uval - I(User_value); - return 0; - } - for(; i < len; i++){ - command = buf[i]; - if(!command) continue; // omit zero - switch (command){ - case 'A': - P("ADC: "); - print_int(ADC1_DR); - P("ADU\n"); - break; - case 'D': - if(!start_ultrasonic()) - P("Can't start: another measurement is in process!\n"); - break; - case 'H': // show help - help(); - break; - case 'I': - init_sharp_sensor(); - break; - case 'S': - cont = !cont; - if(cont) start_ultrasonic(); - break; - case 'T': - newline(); - print_int(Timer); // be careful for Time >= 2^{31}!!! - newline(); - break; - case '\n': // show newline, space and tab as is - case '\r': - case ' ': - case '\t': - break; - default: - command = '?'; // echo '?' on unknown command in byte mode - } - usb_send(command); // echo readed byte - } - return 0; // all data processed - 0 bytes leave in buffer -} - -/** - * Send char array wrd thru USB or UART - */ -void prnt(uint8_t *wrd){ - if(!wrd) return; - while(*wrd) usb_send(*wrd++); -} - -/** - * Read from TTY integer value given by user (in DEC). - * Reading stops on first non-numeric symbol. - * To work with symbol terminals reading don't stops on buffer's end, - * it waits for first non-numeric char. - * When working on string terminals, terminate string by '\n', 0 or any other symbol - * @param buf - buffer to read from - * @param cnt - buffer length - * @return amount of readed symbols - */ -int read_int(char *buf, int cnt){ - int readed = 0, i; - static int enteredDigits; // amount of entered digits - static int sign; // sign of readed value - if(Uval_ready){ // this is first run - Uval_ready = UVAL_START; // clear flag - enteredDigits = 0; // 0 digits entered - User_value = 0; // clear value - sign = 1; // clear sign - } - if(!cnt) return 0; - for(i = 0; i < cnt; i++, readed++){ - uint8_t chr = buf[i]; - if(chr == '-'){ - if(enteredDigits == 0){ // sign should be first - sign = -1; - continue; - }else{ // '-' after number - reject entered value - Uval_ready = UVAL_BAD; - break; - } - } - if(chr < '0' || chr > '9'){ - if(enteredDigits) - Uval_ready = UVAL_ENTERED; - else - Uval_ready = UVAL_BAD; // bad symbol - break; - } - User_value = User_value * 10 + (int32_t)(chr - '0'); - enteredDigits++; - } - if(Uval_ready == UVAL_ENTERED) // reading has met an non-numeric character - User_value *= sign; - return readed; -} - -/** - * Print buff as hex values - * @param buf - buffer to print - * @param l - buf length - * @param s - function to send a byte - */ -void print_hex(uint8_t *buff, uint8_t l){ - void putc(uint8_t c){ - if(c < 10) - usb_send(c + '0'); - else - usb_send(c + 'a' - 10); - } - usb_send('0'); usb_send('x'); // prefix 0x - while(l--){ - putc(buff[l] >> 4); - putc(buff[l] & 0x0f); - } -} - -/** - * Print decimal integer value - * @param N - value to print - * @param s - function to send a byte - */ -void print_int(int32_t N){ - uint8_t buf[10], L = 0; - if(N < 0){ - usb_send('-'); - N = -N; - } - if(N){ - while(N){ - buf[L++] = N % 10 + '0'; - N /= 10; - } - while(L--) usb_send(buf[L]); - }else usb_send('0'); -} - diff --git a/ultrasonic/user_proto.h b/ultrasonic/user_proto.h deleted file mode 100644 index d9af859..0000000 --- a/ultrasonic/user_proto.h +++ /dev/null @@ -1,49 +0,0 @@ -/* - * user_proto.h - * - * Copyright 2014 Edward V. Emelianov - * - * 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., 51 Franklin Street, Fifth Floor, Boston, - * MA 02110-1301, USA. - */ - -#pragma once -#ifndef __USER_PROTO_H__ -#define __USER_PROTO_H__ - -#include "cdcacm.h" - -// shorthand for prnt -#define P(arg) do{prnt((uint8_t*)arg);}while(0) -// debug message - over USB -#ifdef EBUG - #define DBG(a) do{prnt((uint8_t*)a);}while(0) -#else - #define DBG(a) -#endif - -extern uint8_t cont; - -typedef uint8_t (*intfun)(int32_t); - -void prnt(uint8_t *wrd); -#define newline() usb_send('\n') - -void print_int(int32_t N); -void print_hex(uint8_t *buff, uint8_t l); - -int parse_incoming_buf(char *buf, int len); - -#endif // __USER_PROTO_H__