]> jspc29.x-matter.uni-frankfurt.de Git - avr.git/commitdiff
init of code for a Trb5sc AddOn for the CBM RICH detector with a Atmega32u4 uC on...
authorAdrian Weber <adrian.a.weber@exp2.physik.uni-giessen.de>
Mon, 8 Feb 2021 16:42:53 +0000 (17:42 +0100)
committerAdrian Weber <adrian.a.weber@exp2.physik.uni-giessen.de>
Mon, 8 Feb 2021 16:42:53 +0000 (17:42 +0100)
atmega32u4/CbmRich_sensoring/.gitignore [new file with mode: 0644]
atmega32u4/CbmRich_sensoring/Makefile [new file with mode: 0644]
atmega32u4/CbmRich_sensoring/README.md [new file with mode: 0644]
atmega32u4/CbmRich_sensoring/config [new file with mode: 0755]
atmega32u4/CbmRich_sensoring/main.c [new file with mode: 0644]
atmega32u4/CbmRich_sensoring/usb_serial.c [new file with mode: 0644]
atmega32u4/CbmRich_sensoring/usb_serial.h [new file with mode: 0644]

diff --git a/atmega32u4/CbmRich_sensoring/.gitignore b/atmega32u4/CbmRich_sensoring/.gitignore
new file mode 100644 (file)
index 0000000..d40303b
--- /dev/null
@@ -0,0 +1 @@
+./lib/*
diff --git a/atmega32u4/CbmRich_sensoring/Makefile b/atmega32u4/CbmRich_sensoring/Makefile
new file mode 100644 (file)
index 0000000..a4c30de
--- /dev/null
@@ -0,0 +1,231 @@
+# Hey Emacs, this is a -*- makefile -*-
+
+# AVR-GCC Makefile template, derived from the WinAVR template (which
+# is public domain), believed to be neutral to any flavor of "make"
+# (GNU make, BSD make, SysV make)
+
+
+MCU = atmega32u4
+FORMAT = ihex
+TARGET = main
+SRC = $(TARGET).c usb_serial.c lib/1wire/drivers/ow_driver_avr_gpio.c lib/1wire/dallas/dallas.c lib/1wire/onewire/onewire.c
+ASRC = 
+OPT = 2
+PORT=/dev/ttyACM0
+
+# Name of this Makefile (used for "make depend").
+MAKEFILE = Makefile
+
+# Debugging format.
+# Native formats for AVR-GCC's -g are stabs [default], or dwarf-2.
+# AVR (extended) COFF requires stabs, plus an avr-objcopy run.
+DEBUG = stabs
+
+# Compiler flag to set the C Standard level.
+# c89   - "ANSI" C
+# gnu89 - c89 plus GCC extensions
+# c99   - ISO C99 standard (not yet fully implemented)
+# gnu99 - c99 plus GCC extensions
+CSTANDARD = -std=gnu99
+
+# Place -D or -U options here
+CDEFS = -DF_CPU=8000000
+
+# Place -I options here
+#CINCS =
+CINCS = -I. -I./lib/1wire/dallas -I./lib/1wire/onewire -I./lib/1wire/drivers
+
+
+CDEBUG = -g$(DEBUG)
+CWARN = -Wall -Wstrict-prototypes 
+CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums  -Wl,--relax
+#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
+CFLAGS = $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CSTANDARD) $(CEXTRA) $(CTUNING) -DSTR_SERIAL_NUMBER=L\"$(NUMBER)\"
+
+
+#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs 
+
+
+#Additional libraries.
+
+# Minimalistic printf version
+PRINTF_LIB_MIN = -Wl,-u,vfprintf -lprintf_min
+
+# Floating point printf version (requires MATH_LIB = -lm below)
+PRINTF_LIB_FLOAT = -Wl,-u,vfprintf -lprintf_flt
+
+PRINTF_LIB = 
+
+# Minimalistic scanf version
+SCANF_LIB_MIN = -Wl,-u,vfscanf -lscanf_min
+
+# Floating point + %[ scanf version (requires MATH_LIB = -lm below)
+SCANF_LIB_FLOAT = -Wl,-u,vfscanf -lscanf_flt
+
+SCANF_LIB = 
+
+MATH_LIB = -lm
+
+# External memory options
+
+# 64 KB of external RAM, starting after internal RAM (ATmega128!),
+# used for variables (.data/.bss) and heap (malloc()).
+#EXTMEMOPTS = -Wl,--section-start,.data=0x801100,--defsym=__heap_end=0x80ffff
+
+# 64 KB of external RAM, starting after internal RAM (ATmega128!),
+# only used for heap (malloc()).
+#EXTMEMOPTS = -Wl,--defsym=__heap_start=0x801100,--defsym=__heap_end=0x80ffff
+
+EXTMEMOPTS =
+
+#LDMAP = $(LDFLAGS) -Wl,-Map=$(TARGET).map,--cref
+LDFLAGS = $(EXTMEMOPTS) $(LDMAP) $(PRINTF_LIB) $(SCANF_LIB) $(MATH_LIB)
+
+
+# Programming support using avrdude. Settings and variables.
+
+AVRDUDE_PROGRAMMER = dragon_jtag
+AVRDUDE_PORT = usb
+
+AVRDUDE_WRITE_FLASH = -U flash:w:$(TARGET).hex
+#AVRDUDE_WRITE_EEPROM = -U eeprom:w:$(TARGET).eep
+
+
+# Uncomment the following if you want avrdude's erase cycle counter.
+# Note that this counter needs to be initialized first using -Yn,
+# see avrdude manual.
+#AVRDUDE_ERASE_COUNTER = -y
+
+# Uncomment the following if you do /not/ wish a verification to be
+# performed after programming the device.
+AVRDUDE_NO_VERIFY = -V
+
+# Increase verbosity level.  Please use this when submitting bug
+# reports about avrdude. See <http://savannah.nongnu.org/projects/avrdude> 
+# to submit bug reports.
+#AVRDUDE_VERBOSE = -v -v
+
+AVRDUDE_BASIC = -p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER)
+AVRDUDE_FLAGS = $(AVRDUDE_BASIC) $(AVRDUDE_NO_VERIFY) $(AVRDUDE_VERBOSE) $(AVRDUDE_ERASE_COUNTER)
+
+
+CC = avr-gcc
+OBJCOPY = avr-objcopy
+OBJDUMP = avr-objdump
+SIZE = avr-size
+NM = avr-nm
+AVRDUDE = avrdude
+REMOVE = rm -f
+MV = mv -f
+
+# Define all object files.
+OBJ = $(SRC:.c=.o) $(ASRC:.S=.o) 
+
+# Define all listing files.
+LST = $(ASRC:.S=.lst) $(SRC:.c=.lst)
+
+# Combine all necessary flags and optional flags.
+# Add target processor to flags.
+ALL_CFLAGS = -mmcu=$(MCU) -I. $(CFLAGS)
+ALL_ASFLAGS = -mmcu=$(MCU) -I. -x assembler-with-cpp $(ASFLAGS)
+
+
+# Default target.
+all: build
+
+build: elf hex eep
+
+elf: $(TARGET).elf
+hex: $(TARGET).hex
+eep: $(TARGET).eep
+lss: $(TARGET).lss 
+sym: $(TARGET).sym
+
+
+# Program the device.  
+program: $(TARGET).hex $(TARGET).eep
+       $(AVRDUDE) $(AVRDUDE_FLAGS) $(AVRDUDE_WRITE_FLASH) $(AVRDUDE_WRITE_EEPROM)
+
+
+size: 
+       $(SIZE) -C --mcu=$(MCU)   $(TARGET).elf 
+
+# Convert ELF to COFF for use in debugging / simulating in AVR Studio or VMLAB.
+COFFCONVERT=$(OBJCOPY) --debugging \
+--change-section-address .data-0x800000 \
+--change-section-address .bss-0x800000 \
+--change-section-address .noinit-0x800000 \
+--change-section-address .eeprom-0x810000 
+
+
+coff: $(TARGET).elf
+       $(COFFCONVERT) -O coff-avr $(TARGET).elf $(TARGET).cof
+
+
+extcoff: $(TARGET).elf
+       $(COFFCONVERT) -O coff-ext-avr $(TARGET).elf $(TARGET).cof
+
+
+.SUFFIXES: .elf .hex .eep .lss .sym
+
+.elf.hex:
+       $(OBJCOPY) -O $(FORMAT) -R .eeprom $< $@
+
+.elf.eep:
+       -$(OBJCOPY) -j .eeprom --set-section-flags=.eeprom="alloc,load" \
+       --change-section-lma .eeprom=0 -O $(FORMAT) $< $@
+
+# Create extended listing file from ELF output file.
+.elf.lss:
+       $(OBJDUMP) -h -S $< > $@
+
+# Create a symbol table from ELF output file.
+.elf.sym:
+       $(NM) -n $< > $@
+
+
+
+# Link: create ELF output file from object files.
+$(TARGET).elf: $(OBJ)
+       $(CC) $(ALL_CFLAGS) $(OBJ) --output $@ $(LDFLAGS)
+
+
+# Compile: create object files from C source files.
+.c.o:
+       $(CC) -c $(ALL_CFLAGS) $< -o $@ 
+
+
+# Compile: create assembler files from C source files.
+.c.s:
+       $(CC) -S $(ALL_CFLAGS) $< -o $@
+
+
+# Assemble: create object files from assembler source files.
+.S.o:
+       $(CC) -c $(ALL_ASFLAGS) $< -o $@
+
+
+# Target: clean project.
+clean:
+       $(REMOVE) $(TARGET).hex $(TARGET).eep $(TARGET).cof $(TARGET).elf \
+       $(TARGET).map $(TARGET).sym $(TARGET).lss \
+       $(OBJ) $(LST) $(SRC:.c=.s) $(SRC:.c=.d)
+
+depend:
+       if grep '^# DO NOT DELETE' $(MAKEFILE) >/dev/null; \
+       then \
+               sed -e '/^# DO NOT DELETE/,$$d' $(MAKEFILE) > \
+                       $(MAKEFILE).$$$$ && \
+               $(MV) $(MAKEFILE).$$$$ $(MAKEFILE); \
+       fi
+       echo '# DO NOT DELETE THIS LINE -- make depend depends on it.' \
+               >> $(MAKEFILE); \
+       $(CC) -M -mmcu=$(MCU) $(CDEFS) $(CINCS) $(SRC) $(ASRC) >> $(MAKEFILE)
+
+.PHONY:        all build elf hex eep lss sym program coff extcoff clean depend program_bootloader program_arduino
+
+program_bootloader: all
+       dfu-programmer $(MCU) erase && dfu-programmer $(MCU) flash $(TARGET).hex && dfu-programmer $(MCU) start
+
+program_arduino: all
+       avrdude -patmega32u4 -cavr109 -P$(PORT) -b57600 -D -Uflash:w:$(TARGET).hex:i
diff --git a/atmega32u4/CbmRich_sensoring/README.md b/atmega32u4/CbmRich_sensoring/README.md
new file mode 100644 (file)
index 0000000..37516a1
--- /dev/null
@@ -0,0 +1,46 @@
+# RICH Trb5sc Sensoring AddOn board
+
+This firmware is made for the CBM RICH detectors Adapter for the Trb5sc to control the connected sensors via a microcontroller (Atmega32U4).
+
+______________________________________________________________________________________________________________
+
+## Installation
+
+make firmware:
+
+``` bash
+make clean && make NUMBER=55
+```
+Don't forget to change the Serial Number (here 55) to the correct value.
+
+
+flash on promicro:
+
+First, reset the microcontroller via pulling the RST pin to GND.
+
+Afterwards:
+
+``` bash
+/home/adrian/Schreibtisch/arduino-1.8.13/hardware/tools/avr/bin/avrdude -C/home/adrian/Schreibtisch/arduino-1.8.13/hardware/tools/avr/etc/avrdude.conf -v -patmega32u4 -cavr109 -P/dev/ttyACM0 -b57600 -D -Uflash:w:./main.hex:i
+```
+
+If your (Linux) System has problems with flashing, try to stop the ModemManager:
+
+``` bash
+systemctl stop ModemManager.service
+```
+
+If the board was already flashed, the HWB Pin has to be pulled to GND and simuktaneously the RESET Pin has to be pulled to GND. NOw the board enters the Bootloader.
+
+After flashing with microUSB, please unplug the cable and plug the adapter. Keep in mind to plug the GND connection too.
+
+______________________________________________________________________________________________________________
+
+## Register definition
+
+______________________________________________________________________________________________________________
+
+## Protokoll definition
+
+______________________________________________________________________________________________________________
+## Usage
diff --git a/atmega32u4/CbmRich_sensoring/config b/atmega32u4/CbmRich_sensoring/config
new file mode 100755 (executable)
index 0000000..47821b3
--- /dev/null
@@ -0,0 +1,9 @@
+#!/bin/bash
+
+echo "config the CBM RICH sensoring uC sources"
+
+make lib;
+make lib/1wire/;
+
+git clone https://github.com/darauble/DallasOneWire.git ./lib/1wire/
+
diff --git a/atmega32u4/CbmRich_sensoring/main.c b/atmega32u4/CbmRich_sensoring/main.c
new file mode 100644 (file)
index 0000000..c71fc0e
--- /dev/null
@@ -0,0 +1,323 @@
+// #define F_CPU 8000000UL
+
+#include <avr/interrupt.h>
+#include <util/delay.h>
+#include <avr/io.h>
+#include <avr/eeprom.h>
+#include <string.h>
+#include <avr/pgmspace.h>
+
+#include "ow_driver.h"
+#include "ow_driver_avr_gpio.h"
+#include "onewire.h"
+#include "dallas.h"
+
+#include <stdio.h>
+
+#include <usb_serial.h>
+
+#define FIRMWARE_VERSION 0x001
+
+#define DEBUG_USB_OUT
+
+// BEGIN define 1-wire parameters
+#define MAX_OW_DEV_COUNT_PER_PIN 10
+#define NUM_1W_PINS 3
+
+uint8_t scratch_pad[__SCR_LENGTH];
+uint8_t dev_count[NUM_1W_PINS];
+uint8_t dev_addr[NUM_1W_PINS][MAX_OW_DEV_COUNT_PER_PIN][8];
+uint8_t DS18B20_scratch_pad[__SCR_LENGTH];
+
+// END define 1-wire parameters
+
+uint8_t  cur_meas_line = 0;
+uint8_t  cur_meas_devNbr = 0;
+uint8_t  settings_changed;
+uint16_t time;
+
+uint8_t rxcnt = 0, txpoint = 0;
+uint8_t rxbuf[11];
+uint8_t txbuf[12];
+
+uint8_t tx_test_buf[100];
+
+
+int search_devices(owu_struct_t []);
+int init_OW_measurements(owu_struct_t []);
+int OW_measurements(owu_struct_t []);
+
+/***
+ *  Data:   XuuGcRvvvv
+ *          
+ *          X    - command   (write: W, read: R, answer: A etc.)
+ *          uu   - Controllernumber (Hex value)
+ *          G    - Groupnumber  (to talk to all channels, that belong together, in one command.)
+ *          c    - channelnumber in the group (Hex value)
+ *          R    - register (Hex value)
+ *          vvvv - 16 Bit value 
+ * 
+ *          All in all 10 characters
+ *          
+ * 
+ *          close with a "\n"
+ *          e.g. "RF2012FE51\n"
+ * 
+ ***/
+
+/***
+ *  Registers  |  description
+ *  ------------------------------  
+ *     0       |  DCDC On/Off -> not avail. for  <= Rev1_2
+ *     1       |  DCDC set voltage adjustment resistors
+ *     2       |  Voltage V_in
+ *     3       |  Current C_in
+ *     4       |  Temperature
+ *     5       |  [15:4] Firmware; [3:2] reserved; [1] Switch ; [0] LED
+ ***/
+
+void getdata(uint8_t buf) {
+  
+} 
+  
+
+ISR(USART1_RX_vect) {
+  //uint8_t buf = UDR1;
+  //getdata(buf);
+  //usb_serial_putchar(buf);
+}
+  
+ISR(USART1_UDRE_vect) {
+  if(txbuf[txpoint] != 0)
+    UDR1 = txbuf[txpoint++];
+  if(txpoint > 11 || txbuf[txpoint] == 0) {  
+    txpoint = 0;
+    UCSR1B &= ~(1<< UDRIE1); //deactivate Transmit
+    }
+  }  
+    
+ISR(TIMER0_OVF_vect) {
+  time++;
+  asm volatile("wdr");
+}    
+  
+int main(void) {
+  
+
+  CLKPR = (1 << CLKPCE); // prescaler 2 = 8 MHz
+  CLKPR = (1 << CLKPS0); // prescaler 2
+  usb_init(); 
+
+ // Configure ports
+    
+  MCUCR |= (1<<JTD);
+  MCUCR |= (1<<JTD);  //yes, twice
+
+  //--------------------------------------------------------//
+  //DDRx  : 0 = Input; 1 = Output
+  //PORTx : Input  ->  0: no PullUp    1: Pullup
+  //        Output ->  0: LOW          1: HIGH
+
+  PORTB = 0b00000110; //CB3|CB2|CB1|CB0|MISO|MOSI|SCL|~CS
+  DDRB  = 0b00000111;
+
+  PORTC = 0b10111111; // -|SEL|-|-|-|-|-|-
+  DDRC  = 0b01000000;
+
+  PORTD = 0b00001111; // CB1|CB3|CB0|CB2|TX|RX|-|-
+  DDRD  = 0b11110000;
+  
+  PORTE = 0b11111111; // LED On; unconn. inputs are with internal PullUp
+  DDRE  = 0b01000000; // -|LED|-|-|-|-|-|-
+
+  PORTF = 0b10001111; // -|DAT|SHCP|STCP|-|-|~MS_RST|~OE
+  DDRF  = 0b01110011;
+  //--------------------------------------------------------//
+  
+  //Timer0 at 30 Hz overflow for ADC control
+  TCCR0B = (5 << CS00);
+  TIMSK0 = (1 << TOIE0); //Overflow interrupt`
+
+  
+  //Init USART    
+  UCSR1A = (1 << U2X1);  // Double Speed Mode
+  //UCSR1A = (0 << U2X1);  // Single Speed Mode
+  UCSR1B = (1 << RXCIE1) | (0 << TXCIE1) | (0 << RXEN1) | (1 << TXEN1);
+  UCSR1C = (3 << UCSZ10); //8 Bit
+  UBRR1  = 0x10; // 38k4 (SSM) //0x33; // 38k4  //0x10; //57600
+  _delay_ms(10);
+  UCSR1B |= (1 << RXEN1);
+  
+  // 1-wire declaration
+  ow_driver_ptr driver_Q[3];
+  owu_struct_t ow_Q[3];
+
+  sei();
+
+  // 1-wire init
+  init_driver(&driver_Q[0], E_PORTD+1); // AVR PD3
+  owu_init(&ow_Q[0], driver_Q[0]);
+  
+  init_driver(&driver_Q[1], E_PORTD+7); // AVR PD4
+  owu_init(&ow_Q[1], driver_Q[1]);
+
+  init_driver(&driver_Q[2], E_PORTD+4); // AVR PD5
+  owu_init(&ow_Q[2], driver_Q[2]);
+
+  //SPI INIT
+  //SPCR    = (1<<SPE)|(1<<MSTR)|(0<<CPOL)|(1<<CPHA)|(0<<SPR0); // 2MHz ; Master; Mode1; Enabled
+  
+  //Watchdog at .5 seconds
+  //WDTCSR = (1<<WDCE);
+  //WDTCSR = (1<<WDE) | (5<<WDP0); 
+  
+  //PORTB |= (1<<PB0); //off
+  //PORTB &= ~(1<<PB0);
+
+  // Start actual firmware behaviour
+  search_devices(ow_Q);
+  init_OW_measurements(ow_Q);
+
+  // here start first scan of all Temp devices that are found
+  //TODO
+  while(1) {
+
+    OW_measurements(ow_Q);
+
+    PORTB |= (1<<PB0);
+    _delay_ms(2000);
+    PORTB &= ~(1<<PB0);
+    _delay_ms(2000);
+  }
+}
+
+void delay_us(uint32_t us)
+{
+       if (--us == 0) return;
+       if (--us == 0) return;
+       us <<= 1; us--;
+
+       __asm__ __volatile__ (
+               "1: sbiw %0,1" "\n\t"
+               "brne 1b" : "=w" (us) : "0" (us)
+       );
+}
+
+
+/**
+ *  SEARCH for all OneWire Devices connected on all selected Ports and safe Addresses
+ **/
+int search_devices(owu_struct_t ow_Q[]){
+  // 1-wire search of boards / addresses > Later in separate function
+  for (uint8_t i = 0; i < NUM_1W_PINS; ++i){
+    dev_count[i] = 0;
+  }
+
+  for (uint8_t ow_line = 0; ow_line < NUM_1W_PINS; ++ow_line){
+    while(owu_search(&ow_Q[ow_line], dev_addr[ow_line][dev_count[ow_line]])) {
+      dev_count[ow_line]++;
+      #ifdef DEBUG_USB_OUT
+        int nbytes = sprintf((char*) tx_test_buf, "Devices found on line %d :  %d\r\n", ow_line, dev_count[ow_line]); 
+        usb_serial_write(tx_test_buf,nbytes);
+        
+        nbytes = sprintf((char*) tx_test_buf, "\t Address:  %x %x %x %x %x %x %x %x\r\n", dev_addr[ow_line][dev_count[ow_line]-1][0],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][1],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][2],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][3],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][4],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][5],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][6],
+                                                                                  dev_addr[ow_line][dev_count[ow_line]-1][7]); 
+        usb_serial_write(tx_test_buf,nbytes);
+      #endif
+
+               //uart_puts(buf);
+               if (dev_count[ow_line] >= MAX_OW_DEV_COUNT_PER_PIN) {
+                       break;
+               }
+         }
+  }
+
+  return 0;
+}
+
+int init_OW_measurements(owu_struct_t ow_Q[]){
+  for (uint8_t ow_line = 0; ow_line < NUM_1W_PINS; ++ow_line){
+    for (uint8_t dev_nbr = 0; dev_nbr < dev_count[ow_line]; ++dev_nbr){
+    
+      // start measurement on device
+      if (dev_addr[ow_line][dev_nbr][0] == 0x28) { // Device is DS18B20
+        ds_convert_device(&ow_Q[ow_line], dev_addr[ow_line][dev_nbr]);
+        
+
+      } else if (dev_addr[ow_line][dev_nbr][0] == 0x19) { // Device is DS28E17
+
+      } else {
+        // error: Action to be defined
+      }
+
+      #ifdef DEBUG_USB_OUT
+        int nbytes = sprintf((char*) tx_test_buf, "\t Start Measurement:  %x%x%x%x%x%x%x%x\r\n", dev_addr[ow_line][dev_nbr][0],
+                                                                                             dev_addr[ow_line][dev_nbr][1],
+                                                                                             dev_addr[ow_line][dev_nbr][2],
+                                                                                             dev_addr[ow_line][dev_nbr][3],
+                                                                                             dev_addr[ow_line][dev_nbr][4],
+                                                                                             dev_addr[ow_line][dev_nbr][5],
+                                                                                             dev_addr[ow_line][dev_nbr][6],
+                                                                                             dev_addr[ow_line][dev_nbr][7]); 
+        usb_serial_write(tx_test_buf,nbytes);
+      #endif
+    }
+  }
+
+  _delay_ms(500);
+
+  return 0;
+}
+
+
+int OW_measurements(owu_struct_t ow_Q[]){
+  // start measurement on device  
+  if (cur_meas_devNbr < dev_count[cur_meas_line]) {
+    int nbytes2 = sprintf((char*) tx_test_buf, "Line:  %d  |  Device %d \n", cur_meas_line, cur_meas_devNbr);
+         usb_serial_write(tx_test_buf,nbytes2);
+
+    if (dev_addr[cur_meas_line][cur_meas_devNbr][0] == 0x28) { // Device is DS18B20
+      ds_read_temp_only(&ow_Q[cur_meas_line], dev_addr[cur_meas_line][cur_meas_devNbr], DS18B20_scratch_pad);
+      #ifdef DEBUG_USB_OUT
+        int nbytes = sprintf((char*) tx_test_buf, "UID:  %x%x%x%x%x%x%x%x \n", dev_addr[cur_meas_line][cur_meas_devNbr][0],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][1],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][2],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][3],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][4],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][5],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][6],
+                                                                                                 dev_addr[cur_meas_line][cur_meas_devNbr][7]); 
+        usb_serial_write(tx_test_buf,nbytes);
+
+        nbytes = sprintf((char*) tx_test_buf, "Temperatur: %d \n", (int16_t) ds_get_raw(DS18B20_scratch_pad));
+                 usb_serial_write(tx_test_buf,nbytes);
+      #endif
+
+      //Start next measurement on selected Device
+      ds_convert_device(&ow_Q[cur_meas_line], dev_addr[cur_meas_line][cur_meas_devNbr]);
+
+    } else if (dev_addr[cur_meas_line][cur_meas_devNbr][0] == 0x19) { // Device is DS28E17
+
+    } else {
+      // error: Action to be defined
+    }
+  }
+
+  // change Device Selection to next Device
+  cur_meas_devNbr++;
+  if (cur_meas_devNbr >= dev_count[cur_meas_line]) {
+    cur_meas_devNbr = 0;
+    cur_meas_line++;
+    if (cur_meas_line >= NUM_1W_PINS) cur_meas_line = 0;
+  }
+
+  return 0;
+}
\ No newline at end of file
diff --git a/atmega32u4/CbmRich_sensoring/usb_serial.c b/atmega32u4/CbmRich_sensoring/usb_serial.c
new file mode 100644 (file)
index 0000000..4f40451
--- /dev/null
@@ -0,0 +1,937 @@
+/* USB Serial Example for Teensy USB Development Board
+ * http://www.pjrc.com/teensy/usb_serial.html
+ * Copyright (c) 2008,2010,2011 PJRC.COM, LLC
+ * 
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ * 
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ * 
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+// Version 1.0: Initial Release
+// Version 1.1: support Teensy++
+// Version 1.2: fixed usb_serial_available
+// Version 1.3: added transmit bandwidth test
+// Version 1.4: added usb_serial_write
+// Version 1.5: add support for Teensy 2.0
+// Version 1.6: fix zero length packet bug
+// Version 1.7: fix usb_serial_set_control
+
+#define USB_SERIAL_PRIVATE_INCLUDE
+#include "usb_serial.h"
+
+
+/**************************************************************************
+ *
+ *  Configurable Options
+ *
+ **************************************************************************/
+
+// You can change these to give your code its own name.  On Windows,
+// these are only used before an INF file (driver install) is loaded.
+#define STR_MANUFACTURER        L"TRB3"
+#define STR_PRODUCT                L"DCDC"
+
+// All USB serial devices are supposed to have a serial number
+// (according to Microsoft).  On windows, a new COM port is created
+// for every unique serial/vendor/product number combination.  If
+// you program 2 identical boards with 2 different serial numbers
+// and they are assigned COM7 and COM8, each will always get the
+// same COM port number because Windows remembers serial numbers.
+//
+// On Mac OS-X, a device file is created automatically which
+// incorperates the serial number, eg, /dev/cu-usbmodem12341
+//
+// Linux by default ignores the serial number, and creates device
+// files named /dev/ttyACM0, /dev/ttyACM1... in the order connected.
+// Udev rules (in /etc/udev/rules.d) can define persistent device
+// names linked to this serial number, as well as permissions, owner
+// and group settings.
+//#define STR_SERIAL_NUMBER        L ## NUMBER
+
+
+// Mac OS-X and Linux automatically load the correct drivers.  On
+// Windows, even though the driver is supplied by Microsoft, an
+// INF file is needed to load the driver.  These numbers need to
+// match the INF file.
+#define VENDOR_ID                0x16C0
+#define PRODUCT_ID                0x047A
+
+// When you write data, it goes into a USB endpoint buffer, which
+// is transmitted to the PC when it becomes full, or after a timeout
+// with no more writes.  Even if you write in exactly packet-size
+// increments, this timeout is used to send a "zero length packet"
+// that tells the PC no more data is expected and it should pass
+// any buffered data to the application that may be waiting.  If
+// you want data sent immediately, call usb_serial_flush_output().
+#define TRANSMIT_FLUSH_TIMEOUT        5   /* in milliseconds */
+
+// If the PC is connected but not "listening", this is the length
+// of time before usb_serial_getchar() returns with an error.  This
+// is roughly equivilant to a real UART simply transmitting the
+// bits on a wire where nobody is listening, except you get an error
+// code which you can ignore for serial-like discard of data, or
+// use to know your data wasn't sent.
+#define TRANSMIT_TIMEOUT        25   /* in milliseconds */
+
+// USB devices are supposed to implment a halt feature, which is
+// rarely (if ever) used.  If you comment this line out, the halt
+// code will be removed, saving 116 bytes of space (gcc 4.3.0).
+// This is not strictly USB compliant, but works with all major
+// operating systems.
+//#define SUPPORT_ENDPOINT_HALT
+
+
+
+/**************************************************************************
+ *
+ *  Endpoint Buffer Configuration
+ *
+ **************************************************************************/
+
+// These buffer sizes are best for most applications, but perhaps if you
+// want more buffering on some endpoint at the expense of others, this
+// is where you can make such changes.  The AT90USB162 has only 176 bytes
+// of DPRAM (USB buffers) and only endpoints 3 & 4 can double buffer.
+
+#define ENDPOINT0_SIZE                16
+#define CDC_ACM_ENDPOINT        2
+#define CDC_RX_ENDPOINT                3
+#define CDC_TX_ENDPOINT                4
+#if defined(__AVR_AT90USB162__)
+#define CDC_ACM_SIZE                16
+#define CDC_ACM_BUFFER                EP_SINGLE_BUFFER
+#define CDC_RX_SIZE                32
+#define CDC_RX_BUFFER                 EP_DOUBLE_BUFFER
+#define CDC_TX_SIZE                32
+#define CDC_TX_BUFFER                EP_DOUBLE_BUFFER
+#else
+#define CDC_ACM_SIZE                16
+#define CDC_ACM_BUFFER                EP_SINGLE_BUFFER
+#define CDC_RX_SIZE                64
+#define CDC_RX_BUFFER                 EP_DOUBLE_BUFFER
+#define CDC_TX_SIZE                64
+#define CDC_TX_BUFFER                EP_DOUBLE_BUFFER
+#endif
+
+static const uint8_t PROGMEM endpoint_config_table[] = {
+        0,
+        1, EP_TYPE_INTERRUPT_IN,  EP_SIZE(CDC_ACM_SIZE) | CDC_ACM_BUFFER,
+        1, EP_TYPE_BULK_OUT,      EP_SIZE(CDC_RX_SIZE) | CDC_RX_BUFFER,
+        1, EP_TYPE_BULK_IN,       EP_SIZE(CDC_TX_SIZE) | CDC_TX_BUFFER
+};
+
+
+/**************************************************************************
+ *
+ *  Descriptor Data
+ *
+ **************************************************************************/
+
+// Descriptors are the data that your computer reads when it auto-detects
+// this USB device (called "enumeration" in USB lingo).  The most commonly
+// changed items are editable at the top of this file.  Changing things
+// in here should only be done by those who've read chapter 9 of the USB
+// spec and relevant portions of any USB class specifications!
+
+static const uint8_t PROGMEM device_descriptor[] = {
+        18,                                        // bLength
+        1,                                        // bDescriptorType
+        0x00, 0x02,                                // bcdUSB
+        2,                                        // bDeviceClass
+        0,                                        // bDeviceSubClass
+        0,                                        // bDeviceProtocol
+        ENDPOINT0_SIZE,                                // bMaxPacketSize0
+        LSB(VENDOR_ID), MSB(VENDOR_ID),                // idVendor
+        LSB(PRODUCT_ID), MSB(PRODUCT_ID),        // idProduct
+        0x00, 0x01,                                // bcdDevice
+        1,                                        // iManufacturer
+        2,                                        // iProduct
+        3,                                        // iSerialNumber
+        1                                        // bNumConfigurations
+};
+
+#define CONFIG1_DESC_SIZE (9+9+5+5+4+5+7+9+7+7)
+static const uint8_t PROGMEM config1_descriptor[CONFIG1_DESC_SIZE] = {
+        // configuration descriptor, USB spec 9.6.3, page 264-266, Table 9-10
+        9,                                         // bLength;
+        2,                                        // bDescriptorType;
+        LSB(CONFIG1_DESC_SIZE),                        // wTotalLength
+        MSB(CONFIG1_DESC_SIZE),
+        2,                                        // bNumInterfaces
+        1,                                        // bConfigurationValue
+        0,                                        // iConfiguration
+        0xC0,                                        // bmAttributes
+        50,                                        // bMaxPower
+        // interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
+        9,                                        // bLength
+        4,                                        // bDescriptorType
+        0,                                        // bInterfaceNumber
+        0,                                        // bAlternateSetting
+        1,                                        // bNumEndpoints
+        0x02,                                        // bInterfaceClass
+        0x02,                                        // bInterfaceSubClass
+        0x01,                                        // bInterfaceProtocol
+        0,                                        // iInterface
+        // CDC Header Functional Descriptor, CDC Spec 5.2.3.1, Table 26
+        5,                                        // bFunctionLength
+        0x24,                                        // bDescriptorType
+        0x00,                                        // bDescriptorSubtype
+        0x10, 0x01,                                // bcdCDC
+        // Call Management Functional Descriptor, CDC Spec 5.2.3.2, Table 27
+        5,                                        // bFunctionLength
+        0x24,                                        // bDescriptorType
+        0x01,                                        // bDescriptorSubtype
+        0x01,                                        // bmCapabilities
+        1,                                        // bDataInterface
+        // Abstract Control Management Functional Descriptor, CDC Spec 5.2.3.3, Table 28
+        4,                                        // bFunctionLength
+        0x24,                                        // bDescriptorType
+        0x02,                                        // bDescriptorSubtype
+        0x06,                                        // bmCapabilities
+        // Union Functional Descriptor, CDC Spec 5.2.3.8, Table 33
+        5,                                        // bFunctionLength
+        0x24,                                        // bDescriptorType
+        0x06,                                        // bDescriptorSubtype
+        0,                                        // bMasterInterface
+        1,                                        // bSlaveInterface0
+        // endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
+        7,                                        // bLength
+        5,                                        // bDescriptorType
+        CDC_ACM_ENDPOINT | 0x80,                // bEndpointAddress
+        0x03,                                        // bmAttributes (0x03=intr)
+        CDC_ACM_SIZE, 0,                        // wMaxPacketSize
+        64,                                        // bInterval
+        // interface descriptor, USB spec 9.6.5, page 267-269, Table 9-12
+        9,                                        // bLength
+        4,                                        // bDescriptorType
+        1,                                        // bInterfaceNumber
+        0,                                        // bAlternateSetting
+        2,                                        // bNumEndpoints
+        0x0A,                                        // bInterfaceClass
+        0x00,                                        // bInterfaceSubClass
+        0x00,                                        // bInterfaceProtocol
+        0,                                        // iInterface
+        // endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
+        7,                                        // bLength
+        5,                                        // bDescriptorType
+        CDC_RX_ENDPOINT,                        // bEndpointAddress
+        0x02,                                        // bmAttributes (0x02=bulk)
+        CDC_RX_SIZE, 0,                                // wMaxPacketSize
+        0,                                        // bInterval
+        // endpoint descriptor, USB spec 9.6.6, page 269-271, Table 9-13
+        7,                                        // bLength
+        5,                                        // bDescriptorType
+        CDC_TX_ENDPOINT | 0x80,                        // bEndpointAddress
+        0x02,                                        // bmAttributes (0x02=bulk)
+        CDC_TX_SIZE, 0,                                // wMaxPacketSize
+        0                                        // bInterval
+};
+
+// If you're desperate for a little extra code memory, these strings
+// can be completely removed if iManufacturer, iProduct, iSerialNumber
+// in the device desciptor are changed to zeros.
+struct usb_string_descriptor_struct {
+        uint8_t bLength;
+        uint8_t bDescriptorType;
+        int16_t wString[];
+};
+static const struct usb_string_descriptor_struct PROGMEM string0 = {
+        4,
+        3,
+        {0x0409}
+};
+static const struct usb_string_descriptor_struct PROGMEM string1 = {
+        sizeof(STR_MANUFACTURER),
+        3,
+        STR_MANUFACTURER
+};
+static const struct usb_string_descriptor_struct PROGMEM string2 = {
+        sizeof(STR_PRODUCT),
+        3,
+        STR_PRODUCT
+};
+static const struct usb_string_descriptor_struct PROGMEM string3 = {
+        sizeof(STR_SERIAL_NUMBER),
+        3,
+        STR_SERIAL_NUMBER
+};
+
+// This table defines which descriptor data is sent for each specific
+// request from the host (in wValue and wIndex).
+static const struct descriptor_list_struct {
+        uint16_t        wValue;
+        uint16_t        wIndex;
+        const uint8_t        *addr;
+        uint8_t                length;
+} PROGMEM descriptor_list[] = {
+        {0x0100, 0x0000, device_descriptor, sizeof(device_descriptor)},
+        {0x0200, 0x0000, config1_descriptor, sizeof(config1_descriptor)},
+        {0x0300, 0x0000, (const uint8_t *)&string0, 4},
+        {0x0301, 0x0409, (const uint8_t *)&string1, sizeof(STR_MANUFACTURER)},
+        {0x0302, 0x0409, (const uint8_t *)&string2, sizeof(STR_PRODUCT)},
+        {0x0303, 0x0409, (const uint8_t *)&string3, sizeof(STR_SERIAL_NUMBER)}
+};
+#define NUM_DESC_LIST (sizeof(descriptor_list)/sizeof(struct descriptor_list_struct))
+
+
+/**************************************************************************
+ *
+ *  Variables - these are the only non-stack RAM usage
+ *
+ **************************************************************************/
+
+// zero when we are not configured, non-zero when enumerated
+static volatile uint8_t usb_configuration=0;
+
+// the time remaining before we transmit any partially full
+// packet, or send a zero length packet.
+static volatile uint8_t transmit_flush_timer=0;
+static uint8_t transmit_previous_timeout=0;
+
+// serial port settings (baud rate, control signals, etc) set
+// by the PC.  These are ignored, but kept in RAM.
+static uint8_t cdc_line_coding[7]={0x00, 0xE1, 0x00, 0x00, 0x00, 0x00, 0x08};
+static uint8_t cdc_line_rtsdtr=0;
+
+
+/**************************************************************************
+ *
+ *  Public Functions - these are the API intended for the user
+ *
+ **************************************************************************/
+
+// initialize USB serial
+void usb_init(void)
+{
+        HW_CONFIG();
+        USB_FREEZE();                                // enable USB
+        PLL_CONFIG();                                // config PLL, 16 MHz xtal
+        while (!(PLLCSR & (1<<PLOCK))) ;        // wait for PLL lock
+        USB_CONFIG();                                // start USB clock
+        UDCON = 0;                                // enable attach resistor
+        usb_configuration = 0;
+        cdc_line_rtsdtr = 0;
+        UDIEN = (1<<EORSTE)|(1<<SOFE);
+        sei();
+}
+
+// return 0 if the USB is not configured, or the configuration
+// number selected by the HOST
+uint8_t usb_configured(void)
+{
+        return usb_configuration;
+}
+
+// get the next character, or -1 if nothing received
+int16_t usb_serial_getchar(void)
+{
+        uint8_t c, intr_state;
+
+        // interrupts are disabled so these functions can be
+        // used from the main program or interrupt context,
+        // even both in the same program!
+        intr_state = SREG;
+        cli();
+        if (!usb_configuration) {
+                SREG = intr_state;
+                return -1;
+        }
+        UENUM = CDC_RX_ENDPOINT;
+        retry:
+        c = UEINTX;
+        if (!(c & (1<<RWAL))) {
+                // no data in buffer
+                if (c & (1<<RXOUTI)) {
+                        UEINTX = 0x6B;
+                        goto retry;
+                }        
+                SREG = intr_state;
+                return -1;
+        }
+        // take one byte out of the buffer
+        c = UEDATX;
+        // if buffer completely used, release it
+        if (!(UEINTX & (1<<RWAL))) UEINTX = 0x6B;
+        SREG = intr_state;
+        return c;
+}
+
+// number of bytes available in the receive buffer
+uint8_t usb_serial_available(void)
+{
+        uint8_t n=0, i, intr_state;
+
+        intr_state = SREG;
+        cli();
+        if (usb_configuration) {
+                UENUM = CDC_RX_ENDPOINT;
+                n = UEBCLX;
+                if (!n) {
+                        i = UEINTX;
+                        if (i & (1<<RXOUTI) && !(i & (1<<RWAL))) UEINTX = 0x6B;
+                }
+        }
+        SREG = intr_state;
+        return n;
+}
+
+// discard any buffered input
+void usb_serial_flush_input(void)
+{
+        uint8_t intr_state;
+
+        if (usb_configuration) {
+                intr_state = SREG;
+                cli();
+                UENUM = CDC_RX_ENDPOINT;
+                while ((UEINTX & (1<<RWAL))) {
+                        UEINTX = 0x6B; 
+                }
+                SREG = intr_state;
+        }
+}
+
+// transmit a character.  0 returned on success, -1 on error
+int8_t usb_serial_putchar(uint8_t c)
+{
+        uint8_t timeout, intr_state;
+
+        // if we're not online (enumerated and configured), error
+        if (!usb_configuration) return -1;
+        // interrupts are disabled so these functions can be
+        // used from the main program or interrupt context,
+        // even both in the same program!
+        intr_state = SREG;
+        cli();
+        UENUM = CDC_TX_ENDPOINT;
+        // if we gave up due to timeout before, don't wait again
+        if (transmit_previous_timeout) {
+                if (!(UEINTX & (1<<RWAL))) {
+                        SREG = intr_state;
+                        return -1;
+                }
+                transmit_previous_timeout = 0;
+        }
+        // wait for the FIFO to be ready to accept data
+        timeout = UDFNUML + TRANSMIT_TIMEOUT;
+        while (1) {
+                // are we ready to transmit?
+                if (UEINTX & (1<<RWAL)) break;
+                SREG = intr_state;
+                // have we waited too long?  This happens if the user
+                // is not running an application that is listening
+                if (UDFNUML == timeout) {
+                        transmit_previous_timeout = 1;
+                        return -1;
+                }
+                // has the USB gone offline?
+                if (!usb_configuration) return -1;
+                // get ready to try checking again
+                intr_state = SREG;
+                cli();
+                UENUM = CDC_TX_ENDPOINT;
+        }
+        // actually write the byte into the FIFO
+        UEDATX = c;
+        // if this completed a packet, transmit it now!
+        if (!(UEINTX & (1<<RWAL))) UEINTX = 0x3A;
+        transmit_flush_timer = TRANSMIT_FLUSH_TIMEOUT;
+        SREG = intr_state;
+        return 0;
+}
+
+
+// transmit a character, but do not wait if the buffer is full,
+//   0 returned on success, -1 on buffer full or error 
+int8_t usb_serial_putchar_nowait(uint8_t c)
+{
+        uint8_t intr_state;
+
+        if (!usb_configuration) return -1;
+        intr_state = SREG;
+        cli();
+        UENUM = CDC_TX_ENDPOINT;
+        if (!(UEINTX & (1<<RWAL))) {
+                // buffer is full
+                SREG = intr_state;
+                return -1;
+        }
+        // actually write the byte into the FIFO
+        UEDATX = c;
+                // if this completed a packet, transmit it now!
+        if (!(UEINTX & (1<<RWAL))) UEINTX = 0x3A;
+        transmit_flush_timer = TRANSMIT_FLUSH_TIMEOUT;
+        SREG = intr_state;
+        return 0;
+}
+
+// transmit a buffer.
+//  0 returned on success, -1 on error
+// This function is optimized for speed!  Each call takes approx 6.1 us overhead
+// plus 0.25 us per byte.  12 Mbit/sec USB has 8.67 us per-packet overhead and
+// takes 0.67 us per byte.  If called with 64 byte packet-size blocks, this function
+// can transmit at full USB speed using 43% CPU time.  The maximum theoretical speed
+// is 19 packets per USB frame, or 1216 kbytes/sec.  However, bulk endpoints have the
+// lowest priority, so any other USB devices will likely reduce the speed.  Speed
+// can also be limited by how quickly the PC-based software reads data, as the host
+// controller in the PC will not allocate bandwitdh without a pending read request.
+// (thanks to Victor Suarez for testing and feedback and initial code)
+
+int8_t usb_serial_write(const uint8_t *buffer, uint16_t size)
+{
+        uint8_t timeout, intr_state, write_size;
+
+        // if we're not online (enumerated and configured), error
+        if (!usb_configuration) return -1;
+        // interrupts are disabled so these functions can be
+        // used from the main program or interrupt context,
+        // even both in the same program!
+        intr_state = SREG;
+        cli();
+        UENUM = CDC_TX_ENDPOINT;
+        // if we gave up due to timeout before, don't wait again
+        if (transmit_previous_timeout) {
+                if (!(UEINTX & (1<<RWAL))) {
+                        SREG = intr_state;
+                        return -1;
+                }
+                transmit_previous_timeout = 0;
+        }
+        // each iteration of this loop transmits a packet
+        while (size) {
+                // wait for the FIFO to be ready to accept data
+                timeout = UDFNUML + TRANSMIT_TIMEOUT;
+                while (1) {
+                        // are we ready to transmit?
+                        if (UEINTX & (1<<RWAL)) break;
+                        SREG = intr_state;
+                        // have we waited too long?  This happens if the user
+                        // is not running an application that is listening
+                        if (UDFNUML == timeout) {
+                                transmit_previous_timeout = 1;
+                                return -1;
+                        }
+                        // has the USB gone offline?
+                        if (!usb_configuration) return -1;
+                        // get ready to try checking again
+                        intr_state = SREG;
+                        cli();
+                        UENUM = CDC_TX_ENDPOINT;
+                }
+
+                // compute how many bytes will fit into the next packet
+                write_size = CDC_TX_SIZE - UEBCLX;
+                if (write_size > size) write_size = size;
+                size -= write_size;
+
+                // write the packet
+                switch (write_size) {
+                        #if (CDC_TX_SIZE == 64)
+                        case 64: UEDATX = *buffer++;
+                        case 63: UEDATX = *buffer++;
+                        case 62: UEDATX = *buffer++;
+                        case 61: UEDATX = *buffer++;
+                        case 60: UEDATX = *buffer++;
+                        case 59: UEDATX = *buffer++;
+                        case 58: UEDATX = *buffer++;
+                        case 57: UEDATX = *buffer++;
+                        case 56: UEDATX = *buffer++;
+                        case 55: UEDATX = *buffer++;
+                        case 54: UEDATX = *buffer++;
+                        case 53: UEDATX = *buffer++;
+                        case 52: UEDATX = *buffer++;
+                        case 51: UEDATX = *buffer++;
+                        case 50: UEDATX = *buffer++;
+                        case 49: UEDATX = *buffer++;
+                        case 48: UEDATX = *buffer++;
+                        case 47: UEDATX = *buffer++;
+                        case 46: UEDATX = *buffer++;
+                        case 45: UEDATX = *buffer++;
+                        case 44: UEDATX = *buffer++;
+                        case 43: UEDATX = *buffer++;
+                        case 42: UEDATX = *buffer++;
+                        case 41: UEDATX = *buffer++;
+                        case 40: UEDATX = *buffer++;
+                        case 39: UEDATX = *buffer++;
+                        case 38: UEDATX = *buffer++;
+                        case 37: UEDATX = *buffer++;
+                        case 36: UEDATX = *buffer++;
+                        case 35: UEDATX = *buffer++;
+                        case 34: UEDATX = *buffer++;
+                        case 33: UEDATX = *buffer++;
+                        #endif
+                        #if (CDC_TX_SIZE >= 32)
+                        case 32: UEDATX = *buffer++;
+                        case 31: UEDATX = *buffer++;
+                        case 30: UEDATX = *buffer++;
+                        case 29: UEDATX = *buffer++;
+                        case 28: UEDATX = *buffer++;
+                        case 27: UEDATX = *buffer++;
+                        case 26: UEDATX = *buffer++;
+                        case 25: UEDATX = *buffer++;
+                        case 24: UEDATX = *buffer++;
+                        case 23: UEDATX = *buffer++;
+                        case 22: UEDATX = *buffer++;
+                        case 21: UEDATX = *buffer++;
+                        case 20: UEDATX = *buffer++;
+                        case 19: UEDATX = *buffer++;
+                        case 18: UEDATX = *buffer++;
+                        case 17: UEDATX = *buffer++;
+                        #endif
+                        #if (CDC_TX_SIZE >= 16)
+                        case 16: UEDATX = *buffer++;
+                        case 15: UEDATX = *buffer++;
+                        case 14: UEDATX = *buffer++;
+                        case 13: UEDATX = *buffer++;
+                        case 12: UEDATX = *buffer++;
+                        case 11: UEDATX = *buffer++;
+                        case 10: UEDATX = *buffer++;
+                        case  9: UEDATX = *buffer++;
+                        #endif
+                        case  8: UEDATX = *buffer++;
+                        case  7: UEDATX = *buffer++;
+                        case  6: UEDATX = *buffer++;
+                        case  5: UEDATX = *buffer++;
+                        case  4: UEDATX = *buffer++;
+                        case  3: UEDATX = *buffer++;
+                        case  2: UEDATX = *buffer++;
+                        default:
+                        case  1: UEDATX = *buffer++;
+                        case  0: break;
+                }
+                // if this completed a packet, transmit it now!
+                if (!(UEINTX & (1<<RWAL))) UEINTX = 0x3A;
+                transmit_flush_timer = TRANSMIT_FLUSH_TIMEOUT;
+                SREG = intr_state;
+        }
+        return 0;
+}
+
+
+// immediately transmit any buffered output.
+// This doesn't actually transmit the data - that is impossible!
+// USB devices only transmit when the host allows, so the best
+// we can do is release the FIFO buffer for when the host wants it
+void usb_serial_flush_output(void)
+{
+        uint8_t intr_state;
+
+        intr_state = SREG;
+        cli();
+        if (transmit_flush_timer) {
+                UENUM = CDC_TX_ENDPOINT;
+                UEINTX = 0x3A;
+                transmit_flush_timer = 0;
+        }
+        SREG = intr_state;
+}
+
+// functions to read the various async serial settings.  These
+// aren't actually used by USB at all (communication is always
+// at full USB speed), but they are set by the host so we can
+// set them properly if we're converting the USB to a real serial
+// communication
+uint32_t usb_serial_get_baud(void)
+{
+        return *(uint32_t *)cdc_line_coding;
+}
+uint8_t usb_serial_get_stopbits(void)
+{
+        return cdc_line_coding[4];
+}
+uint8_t usb_serial_get_paritytype(void)
+{
+        return cdc_line_coding[5];
+}
+uint8_t usb_serial_get_numbits(void)
+{
+        return cdc_line_coding[6];
+}
+uint8_t usb_serial_get_control(void)
+{
+        return cdc_line_rtsdtr;
+}
+// write the control signals, DCD, DSR, RI, etc
+// There is no CTS signal.  If software on the host has transmitted
+// data to you but you haven't been calling the getchar function,
+// it remains buffered (either here or on the host) and can not be
+// lost because you weren't listening at the right time, like it
+// would in real serial communication.
+int8_t usb_serial_set_control(uint8_t signals)
+{
+        uint8_t intr_state;
+
+        intr_state = SREG;
+        cli();
+        if (!usb_configuration) {
+                // we're not enumerated/configured
+                SREG = intr_state;
+                return -1;
+        }
+
+        UENUM = CDC_ACM_ENDPOINT;
+        if (!(UEINTX & (1<<RWAL))) {
+                // unable to write
+                // TODO; should this try to abort the previously
+                // buffered message??
+                SREG = intr_state;
+                return -1;
+        }
+        UEDATX = 0xA1;
+        UEDATX = 0x20;
+        UEDATX = 0;
+        UEDATX = 0;
+        UEDATX = 0; // 0 seems to work nicely.  what if this is 1??
+        UEDATX = 0;
+        UEDATX = 1;
+        UEDATX = 0;
+        UEDATX = signals;
+        UEINTX = 0x3A;
+        SREG = intr_state;
+        return 0;
+}
+
+
+
+/**************************************************************************
+ *
+ *  Private Functions - not intended for general user consumption....
+ *
+ **************************************************************************/
+
+
+// USB Device Interrupt - handle all device-level events
+// the transmit buffer flushing is triggered by the start of frame
+//
+ISR(USB_GEN_vect)
+{
+        uint8_t intbits, t;
+
+        intbits = UDINT;
+        UDINT = 0;
+        if (intbits & (1<<EORSTI)) {
+                UENUM = 0;
+                UECONX = 1;
+                UECFG0X = EP_TYPE_CONTROL;
+                UECFG1X = EP_SIZE(ENDPOINT0_SIZE) | EP_SINGLE_BUFFER;
+                UEIENX = (1<<RXSTPE);
+                usb_configuration = 0;
+                cdc_line_rtsdtr = 0;
+        }
+        if (intbits & (1<<SOFI)) {
+                if (usb_configuration) {
+                        t = transmit_flush_timer;
+                        if (t) {
+                                transmit_flush_timer = --t;
+                                if (!t) {
+                                        UENUM = CDC_TX_ENDPOINT;
+                                        UEINTX = 0x3A;
+                                }
+                        }
+                }
+        }
+}
+
+
+// Misc functions to wait for ready and send/receive packets
+static inline void usb_wait_in_ready(void)
+{
+        while (!(UEINTX & (1<<TXINI))) ;
+}
+static inline void usb_send_in(void)
+{
+        UEINTX = ~(1<<TXINI);
+}
+static inline void usb_wait_receive_out(void)
+{
+        while (!(UEINTX & (1<<RXOUTI))) ;
+}
+static inline void usb_ack_out(void)
+{
+        UEINTX = ~(1<<RXOUTI);
+}
+
+
+
+// USB Endpoint Interrupt - endpoint 0 is handled here.  The
+// other endpoints are manipulated by the user-callable
+// functions, and the start-of-frame interrupt.
+//
+ISR(USB_COM_vect)
+{
+        uint8_t intbits;
+        const uint8_t *list;
+        const uint8_t *cfg;
+        uint8_t i, n, len, en;
+        uint8_t *p;
+        uint8_t bmRequestType;
+        uint8_t bRequest;
+        uint16_t wValue;
+        uint16_t wIndex;
+        uint16_t wLength;
+        uint16_t desc_val;
+        const uint8_t *desc_addr;
+        uint8_t        desc_length;
+
+        UENUM = 0;
+        intbits = UEINTX;
+        if (intbits & (1<<RXSTPI)) {
+                bmRequestType = UEDATX;
+                bRequest = UEDATX;
+                wValue = UEDATX;
+                wValue |= (UEDATX << 8);
+                wIndex = UEDATX;
+                wIndex |= (UEDATX << 8);
+                wLength = UEDATX;
+                wLength |= (UEDATX << 8);
+                UEINTX = ~((1<<RXSTPI) | (1<<RXOUTI) | (1<<TXINI));
+                if (bRequest == GET_DESCRIPTOR) {
+                        list = (const uint8_t *)descriptor_list;
+                        for (i=0; ; i++) {
+                                if (i >= NUM_DESC_LIST) {
+                                        UECONX = (1<<STALLRQ)|(1<<EPEN);  //stall
+                                        return;
+                                }
+                                desc_val = pgm_read_word(list);
+                                if (desc_val != wValue) {
+                                        list += sizeof(struct descriptor_list_struct);
+                                        continue;
+                                }
+                                list += 2;
+                                desc_val = pgm_read_word(list);
+                                if (desc_val != wIndex) {
+                                        list += sizeof(struct descriptor_list_struct)-2;
+                                        continue;
+                                }
+                                list += 2;
+                                desc_addr = (const uint8_t *)pgm_read_word(list);
+                                list += 2;
+                                desc_length = pgm_read_byte(list);
+                                break;
+                        }
+                        len = (wLength < 256) ? wLength : 255;
+                        if (len > desc_length) len = desc_length;
+                        do {
+                                // wait for host ready for IN packet
+                                do {
+                                        i = UEINTX;
+                                } while (!(i & ((1<<TXINI)|(1<<RXOUTI))));
+                                if (i & (1<<RXOUTI)) return;        // abort
+                                // send IN packet
+                                n = len < ENDPOINT0_SIZE ? len : ENDPOINT0_SIZE;
+                                for (i = n; i; i--) {
+                                        UEDATX = pgm_read_byte(desc_addr++);
+                                }
+                                len -= n;
+                                usb_send_in();
+                        } while (len || n == ENDPOINT0_SIZE);
+                        return;
+                }
+                if (bRequest == SET_ADDRESS) {
+                        usb_send_in();
+                        usb_wait_in_ready();
+                        UDADDR = wValue | (1<<ADDEN);
+                        return;
+                }
+                if (bRequest == SET_CONFIGURATION && bmRequestType == 0) {
+                        usb_configuration = wValue;
+                        cdc_line_rtsdtr = 0;
+                        transmit_flush_timer = 0;
+                        usb_send_in();
+                        cfg = endpoint_config_table;
+                        for (i=1; i<5; i++) {
+                                UENUM = i;
+                                en = pgm_read_byte(cfg++);
+                                UECONX = en;
+                                if (en) {
+                                        UECFG0X = pgm_read_byte(cfg++);
+                                        UECFG1X = pgm_read_byte(cfg++);
+                                }
+                        }
+                        UERST = 0x1E;
+                        UERST = 0;
+                        return;
+                }
+                if (bRequest == GET_CONFIGURATION && bmRequestType == 0x80) {
+                        usb_wait_in_ready();
+                        UEDATX = usb_configuration;
+                        usb_send_in();
+                        return;
+                }
+                if (bRequest == CDC_GET_LINE_CODING && bmRequestType == 0xA1) {
+                        usb_wait_in_ready();
+                        p = cdc_line_coding;
+                        for (i=0; i<7; i++) {
+                                UEDATX = *p++;
+                        }
+                        usb_send_in();
+                        return;
+                }
+                if (bRequest == CDC_SET_LINE_CODING && bmRequestType == 0x21) {
+                        usb_wait_receive_out();
+                        p = cdc_line_coding;
+                        for (i=0; i<7; i++) {
+                                *p++ = UEDATX;
+                        }
+                        usb_ack_out();
+                        usb_send_in();
+                        return;
+                }
+                if (bRequest == CDC_SET_CONTROL_LINE_STATE && bmRequestType == 0x21) {
+                        cdc_line_rtsdtr = wValue;
+                        usb_wait_in_ready();
+                        usb_send_in();
+                        return;
+                }
+                if (bRequest == GET_STATUS) {
+                        usb_wait_in_ready();
+                        i = 0;
+                        #ifdef SUPPORT_ENDPOINT_HALT
+                        if (bmRequestType == 0x82) {
+                                UENUM = wIndex;
+                                if (UECONX & (1<<STALLRQ)) i = 1;
+                                UENUM = 0;
+                        }
+                        #endif
+                        UEDATX = i;
+                        UEDATX = 0;
+                        usb_send_in();
+                        return;
+                }
+                #ifdef SUPPORT_ENDPOINT_HALT
+                if ((bRequest == CLEAR_FEATURE || bRequest == SET_FEATURE)
+                  && bmRequestType == 0x02 && wValue == 0) {
+                        i = wIndex & 0x7F;
+                        if (i >= 1 && i <= MAX_ENDPOINT) {
+                                usb_send_in();
+                                UENUM = i;
+                                if (bRequest == SET_FEATURE) {
+                                        UECONX = (1<<STALLRQ)|(1<<EPEN);
+                                } else {
+                                        UECONX = (1<<STALLRQC)|(1<<RSTDT)|(1<<EPEN);
+                                        UERST = (1 << i);
+                                        UERST = 0;
+                                }
+                                return;
+                        }
+                }
+                #endif
+        }
+        UECONX = (1<<STALLRQ) | (1<<EPEN);        // stall
+}
+
+
diff --git a/atmega32u4/CbmRich_sensoring/usb_serial.h b/atmega32u4/CbmRich_sensoring/usb_serial.h
new file mode 100644 (file)
index 0000000..14c5b1a
--- /dev/null
@@ -0,0 +1,124 @@
+#ifndef usb_serial_h__
+#define usb_serial_h__
+
+#include <stdint.h>
+
+// setup
+void usb_init(void);                   // initialize everything
+uint8_t usb_configured(void);          // is the USB port configured
+
+// receiving data
+int16_t usb_serial_getchar(void);      // receive a character (-1 if timeout/error)
+uint8_t usb_serial_available(void);    // number of bytes in receive buffer
+void usb_serial_flush_input(void);     // discard any buffered input
+
+// transmitting data
+int8_t usb_serial_putchar(uint8_t c);  // transmit a character
+int8_t usb_serial_putchar_nowait(uint8_t c);  // transmit a character, do not wait
+int8_t usb_serial_write(const uint8_t *buffer, uint16_t size); // transmit a buffer
+void usb_serial_flush_output(void);    // immediately transmit any buffered output
+
+// serial parameters
+uint32_t usb_serial_get_baud(void);    // get the baud rate
+uint8_t usb_serial_get_stopbits(void); // get the number of stop bits
+uint8_t usb_serial_get_paritytype(void);// get the parity type
+uint8_t usb_serial_get_numbits(void);  // get the number of data bits
+uint8_t usb_serial_get_control(void);  // get the RTS and DTR signal state
+int8_t usb_serial_set_control(uint8_t signals); // set DSR, DCD, RI, etc
+
+// constants corresponding to the various serial parameters
+#define USB_SERIAL_DTR                 0x01
+#define USB_SERIAL_RTS                 0x02
+#define USB_SERIAL_1_STOP              0
+#define USB_SERIAL_1_5_STOP            1
+#define USB_SERIAL_2_STOP              2
+#define USB_SERIAL_PARITY_NONE         0
+#define USB_SERIAL_PARITY_ODD          1
+#define USB_SERIAL_PARITY_EVEN         2
+#define USB_SERIAL_PARITY_MARK         3
+#define USB_SERIAL_PARITY_SPACE                4
+#define USB_SERIAL_DCD                 0x01
+#define USB_SERIAL_DSR                 0x02
+#define USB_SERIAL_BREAK               0x04
+#define USB_SERIAL_RI                  0x08
+#define USB_SERIAL_FRAME_ERR           0x10
+#define USB_SERIAL_PARITY_ERR          0x20
+#define USB_SERIAL_OVERRUN_ERR         0x40
+
+// This file does not include the HID debug functions, so these empty
+// macros replace them with nothing, so users can compile code that
+// has calls to these functions.
+#define usb_debug_putchar(c)
+#define usb_debug_flush_output()
+
+
+
+// Everything below this point is only intended for usb_serial.c
+#ifdef USB_SERIAL_PRIVATE_INCLUDE
+#include <avr/io.h>
+#include <avr/pgmspace.h>
+#include <avr/interrupt.h>
+
+#define EP_TYPE_CONTROL                        0x00
+#define EP_TYPE_BULK_IN                        0x81
+#define EP_TYPE_BULK_OUT               0x80
+#define EP_TYPE_INTERRUPT_IN           0xC1
+#define EP_TYPE_INTERRUPT_OUT          0xC0
+#define EP_TYPE_ISOCHRONOUS_IN         0x41
+#define EP_TYPE_ISOCHRONOUS_OUT                0x40
+#define EP_SINGLE_BUFFER               0x02
+#define EP_DOUBLE_BUFFER               0x06
+#define EP_SIZE(s)     ((s) == 64 ? 0x30 :     \
+                       ((s) == 32 ? 0x20 :     \
+                       ((s) == 16 ? 0x10 :     \
+                                    0x00)))
+
+#define MAX_ENDPOINT           4
+
+#define LSB(n) (n & 255)
+#define MSB(n) ((n >> 8) & 255)
+
+#if defined(__AVR_AT90USB162__)
+#define HW_CONFIG() 
+#define PLL_CONFIG() (PLLCSR = ((1<<PLLE)|(1<<PLLP0)))
+#define USB_CONFIG() (USBCON = (1<<USBE))
+#define USB_FREEZE() (USBCON = ((1<<USBE)|(1<<FRZCLK)))
+#elif defined(__AVR_ATmega32U4__)
+#define HW_CONFIG() (UHWCON = 0x01)
+#define PLL_CONFIG() (PLLCSR = 0x12)
+#define USB_CONFIG() (USBCON = ((1<<USBE)|(1<<OTGPADE)))
+#define USB_FREEZE() (USBCON = ((1<<USBE)|(1<<FRZCLK)))
+#elif defined(__AVR_AT90USB646__)
+#define HW_CONFIG() (UHWCON = 0x81)
+#define PLL_CONFIG() (PLLCSR = 0x1A)
+#define USB_CONFIG() (USBCON = ((1<<USBE)|(1<<OTGPADE)))
+#define USB_FREEZE() (USBCON = ((1<<USBE)|(1<<FRZCLK)))
+#elif defined(__AVR_AT90USB1286__)
+#define HW_CONFIG() (UHWCON = 0x81)
+#define PLL_CONFIG() (PLLCSR = 0x16)
+#define USB_CONFIG() (USBCON = ((1<<USBE)|(1<<OTGPADE)))
+#define USB_FREEZE() (USBCON = ((1<<USBE)|(1<<FRZCLK)))
+#endif
+
+// standard control endpoint request types
+#define GET_STATUS                     0
+#define CLEAR_FEATURE                  1
+#define SET_FEATURE                    3
+#define SET_ADDRESS                    5
+#define GET_DESCRIPTOR                 6
+#define GET_CONFIGURATION              8
+#define SET_CONFIGURATION              9
+#define GET_INTERFACE                  10
+#define SET_INTERFACE                  11
+// HID (human interface device)
+#define HID_GET_REPORT                 1
+#define HID_GET_PROTOCOL               3
+#define HID_SET_REPORT                 9
+#define HID_SET_IDLE                   10
+#define HID_SET_PROTOCOL               11
+// CDC (communication class device)
+#define CDC_SET_LINE_CODING            0x20
+#define CDC_GET_LINE_CODING            0x21
+#define CDC_SET_CONTROL_LINE_STATE     0x22
+#endif
+#endif