Added Time-lapse tool (USB keyboard emulation)

This commit is contained in:
eddyem 2015-09-01 14:46:00 +03:00
parent 43785dd1f3
commit 20e9313664
29 changed files with 2387 additions and 0 deletions

161
Timelapse_keyboard/GPS.c Normal file
View File

@ -0,0 +1,161 @@
/*
* GPS.c
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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;
set_time(buf);
}else
GPS_status = GPS_NOT_VALID;
}

37
Timelapse_keyboard/GPS.h Normal file
View File

@ -0,0 +1,37 @@
/*
* GPS.h
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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__

133
Timelapse_keyboard/Makefile Normal file
View File

@ -0,0 +1,133 @@
BINARY = timelaps
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)

View File

@ -0,0 +1,35 @@
## 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

140
Timelapse_keyboard/adc.c Normal file
View File

@ -0,0 +1,140 @@
/*
* adc.c - functions for Sharp 2Y0A02 distance meter & photosensor
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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, &current_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, &current_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], &current_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], &current_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;
}
}
}

52
Timelapse_keyboard/adc.h Normal file
View File

@ -0,0 +1,52 @@
/*
* adc.h
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#pragma once
#ifndef __SHARP_H__
#define __SHARP_H__
#include <stdint.h>
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__

View File

@ -0,0 +1,81 @@
/*
* hardware_ini.c - functions for HW initialisation
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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);
*/
}
/**
* 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, &current_time, sizeof(curtime));
}
EXTI_PR = EXTI5;
}
}

View File

@ -0,0 +1,76 @@
/*
* hardware_ini.h
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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__

View File

@ -0,0 +1,74 @@
/*
* keycodes.c
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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;
}

View File

@ -0,0 +1,138 @@
/*
* keycodes.h
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#pragma once
#ifndef __KEYKODES_H__
#define __KEYKODES_H__
#include <stdint.h>
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__

View File

@ -0,0 +1,9 @@
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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

View File

@ -0,0 +1,31 @@
/*
* This file is part of the libopencm3 project.
*
* Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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 <http://www.gnu.org/licenses/>.
*/
/* 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

239
Timelapse_keyboard/main.c Normal file
View File

@ -0,0 +1,239 @@
/*
* main.c
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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 "ultrasonic.h"
#include "adc.h"
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}};
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(void){
uint8_t *string;
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(8999); // 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
tim2_init(); // ultrasonic timer
/*
int i;
for (i = 0; i < 0x80000; 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){
poll_usbkeybrd();
poll_ultrasonic();
poll_ADC();
if((string = check_UART2())){
GPS_parse_answer(string);
}
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){
adctm[i] = msctr;
P("ADC");
put_char_to_buf('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();
}
process_usbkbrd();
}
// 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(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);
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(&current_time, T);
}else
P("Waiting for satellites\n");
}

73
Timelapse_keyboard/main.h Normal file
View File

@ -0,0 +1,73 @@
/*
* main.h
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#pragma once
#ifndef __MAIN_H__
#define __MAIN_H__
#include <stdlib.h>
#include <libopencm3/stm32/exti.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/usart.h>
#include <libopencm3/cm3/nvic.h>
#include <libopencm3/usb/cdc.h>
#include <libopencm3/usb/usbd.h>
#include <libopencm3/usb/hid.h>
#include <libopencm3/cm3/systick.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/stm32/adc.h>
#include <libopencm3/stm32/dma.h>
#include <libopencm3/stm32/spi.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 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__

BIN
Timelapse_keyboard/timelaps.bin Executable file

Binary file not shown.

247
Timelapse_keyboard/uart.c Normal file
View File

@ -0,0 +1,247 @@
/*
* uart.c - functions to work with UART
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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){
// parce 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
}

46
Timelapse_keyboard/uart.h Normal file
View File

@ -0,0 +1,46 @@
/*
* uart.h
*
* Copyright 2014 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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__

View File

@ -0,0 +1,196 @@
/*
* ultrasonic.c
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#include <libopencm3/stm32/timer.h>
#include <libopencm3/stm32/gpio.h>
#include <libopencm3/stm32/rcc.h>
#include <libopencm3/cm3/nvic.h>
#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, &current_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();
}
}

View File

@ -0,0 +1,53 @@
/*
* ultrasonic.h
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*/
#pragma once
#ifndef __ULTRASONIC_H__
#define __ULTRASONIC_H__
#include <stdint.h>
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__

View File

@ -0,0 +1,275 @@
/*
* usbkeybrd.c
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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);
}
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(){
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');
}

View File

@ -0,0 +1,43 @@
/*
* usbkeybrd.h
*
* Copyright 2015 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 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 poll_usbkeybrd() usbd_poll(usbd_dev)
#endif // __USBKEYBRD_H__