summaryrefslogtreecommitdiff
path: root/software
diff options
context:
space:
mode:
authorBernhard Tittelbach <xro@realraum.at>2012-05-17 06:14:25 +0000
committerBernhard Tittelbach <xro@realraum.at>2012-05-17 06:14:25 +0000
commit241a3d8edf2742a91e4b7516237fe55324eedeb6 (patch)
tree526f1c30862e60bd87d5f23cc04a016b71cbdcf1 /software
parentusb lib (diff)
spi and c1101 lib needs to be cleanly separated, code needs to be tested and finished
git-svn-id: https://svn.spreadspace.org/mur.sat@416 7de4ea59-55d0-425e-a1af-a3118ea81d4c
Diffstat (limited to 'software')
-rw-r--r--software/hhd70dongle/c1101lib.c60
-rw-r--r--software/hhd70dongle/c1101lib.h46
-rw-r--r--software/hhd70dongle/hhd70dongle.c43
-rw-r--r--software/hhd70dongle/spi.c234
-rw-r--r--software/hhd70dongle/spi.h2
5 files changed, 356 insertions, 29 deletions
diff --git a/software/hhd70dongle/c1101lib.c b/software/hhd70dongle/c1101lib.c
new file mode 100644
index 0000000..875e6d6
--- /dev/null
+++ b/software/hhd70dongle/c1101lib.c
@@ -0,0 +1,60 @@
+/*
+ *
+ * mur.sat
+ *
+ * Somewhen in the year 2012, mur.at will have a nano satellite launched
+ * into a low earth orbit (310 km above the surface of our planet). The
+ * satellite itself is a TubeSat personal satellite kit, developed and
+ * launched by interorbital systems. mur.sat is a joint venture of mur.at,
+ * ESC im Labor and realraum.
+ *
+ * Please visit the project hompage at sat.mur.at for further information.
+ *
+ *
+ * Copyright (C) 2012 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This file is part of mur.sat.
+ *
+ * mur.sat 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 3 of the License, or
+ * any later version.
+ *
+ * mur.sat is distributed in the hope that 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 mur.sat. If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+#include "avr/io.h"
+#include "util/delay.h"
+
+#include "c1101lib.h"
+#include "spi.h"
+//#include "usb_rawhid.h"
+
+
+#max len: 64 bytes
+void writeTXFifo(char *buffer, len)
+{
+ //check TXBYTES.NUM_TXBYTES
+ // never write more bytes than avaiblabe or doom ensues
+
+
+}
+
+#max returned: 64 bytes
+int readRXFifo(char *buffer)
+{
+ //check RXBYTES.NUM_RXBYTES
+ // never read more bytes than avaiblabe or we will read garbage
+
+ //note: if RX transmission fills fifo buffer at exact same time as last RX Fifo Bit is read via SPI, Fifo Pointer will not be properly updated
+ // and last read byte will be duplicated.
+ // thus: don't last avialable FIFO Bytes unless we can be sure that it will be the last byte of a packet and we can be sure that a following duplicated byte is actually an Fifo duplication and not an actually recieved byte !
+
+
+} \ No newline at end of file
diff --git a/software/hhd70dongle/c1101lib.h b/software/hhd70dongle/c1101lib.h
new file mode 100644
index 0000000..19d057f
--- /dev/null
+++ b/software/hhd70dongle/c1101lib.h
@@ -0,0 +1,46 @@
+/*
+ *
+ * mur.sat
+ *
+ * Somewhen in the year 2012, mur.at will have a nano satellite launched
+ * into a low earth orbit (310 km above the surface of our planet). The
+ * satellite itself is a TubeSat personal satellite kit, developed and
+ * launched by interorbital systems. mur.sat is a joint venture of mur.at,
+ * ESC im Labor and realraum.
+ *
+ * Please visit the project hompage at sat.mur.at for further information.
+ *
+ *
+ * Copyright (C) 2012 Bernhard Tittelbach <xro@realraum.at>
+ *
+ * This file is part of mur.sat.
+ *
+ * mur.sat 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 3 of the License, or
+ * any later version.
+ *
+ * mur.sat is distributed in the hope that 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 mur.sat. If not, see <http://www.gnu.org/licenses/>.
+ *
+ */
+#ifndef MURSAT_c1101lib_h_INCLUDED__
+#define MURSAT_c1101lib_h_INCLUDED__
+
+#define C1101_FIFO_MAX_LEN 64
+
+#max len: 64 bytes
+void writeTXFifo(char *buffer, len);
+
+#max returned: 64 bytes
+int readRXFifo(char *buffer);
+
+#set WakeOnRadio to enabled (true) or disabled(false)
+void setWOR(bool enable);
+
+#endif
diff --git a/software/hhd70dongle/hhd70dongle.c b/software/hhd70dongle/hhd70dongle.c
index 03b4e06..85d9d0f 100644
--- a/software/hhd70dongle/hhd70dongle.c
+++ b/software/hhd70dongle/hhd70dongle.c
@@ -11,7 +11,7 @@
* Please visit the project hompage at sat.mur.at for further information.
*
*
- * Copyright (C) 2011 Christian Pointner <equinox@mur.at>
+ * Copyright (C) 2012 Bernhard Tittelbach <xro@realraum.at>
*
* This file is part of mur.sat.
*
@@ -36,26 +36,67 @@
#include "spi.h"
#include "usb_rawhid.h"
+#define ADCMUX_INTERNALTEMP 0b100111
+#define ADCMUX_ADC12 0b100100
+
#define CPU_PRESCALE(n) (CLKPR = 0x80, CLKPR = (n))
+#define ADC_PRESCALER 0
uint8_t read_buffer[64]; // buffer for reading usb signals
uint8_t write_buffer[64]; // buffer for writing usb signals
+//TODOs:
+// * make as much use of sleep modes as possible
+// * use adc noise canceler (i.e. automatic sampling during cpu sleep)
+// * define and listen for an usb_hid reset command -> jump to bootload address
+// * read atmega temp
+// * safely save state in eeprom (2 memory regions, only use the one with the "written successfully bit" which is written last)
+
+
+int16_t adc_read(uint8_t mux)
+{
+ uint8_t low;
+ char aref = 0b11000000;
+ ADCSRA = (1<<ADEN) | ADC_PRESCALER; // enable ADC
+ ADCSRB = (1<<ADHSM) | (mux & 0x20); // high speed mode
+ ADMUX = aref | (mux & 0x1F); // configure mux input
+ ADCSRA = (1<<ADEN) | ADC_PRESCALER | (1<<ADSC); // start the conversion
+ while (ADCSRA & (1<<ADSC)) ; // wait for result
+ low = ADCL; // must read LSB first
+ ADCSRA &= ~(1<<ADEN); // disable ADC
+ return (ADCH << 8) | low; // must read MSB only once!
+}
+
int main(void)
{
CPU_PRESCALE(0);
led_init();
spi_init();
usb_init();
+ // set PB5/ADC12 to INPUT (c1101 temp sensor)
+ DDRB &= ~(1<<DDB5);
while (!usb_configured()) /* wait */ ;
//int8_t r = usb_rawhid_recv(read_buffer, 0);
//usb_rawhid_send(write_buffer, 23);
+ usb_rawhid_send("hhd70dongle ready",17);
+
+ int16_t c1101_temp = adc_read(ADCMUX_ADC12);
+ int16_t internal_temp = adc_read(ADCMUX_INTERNALTEMP);
for(;;)
{
_delay_ms(250);
led_toggle();
+ c1101_temp = adc_read(ADCMUX_ADC12);
+ internal_temp = adc_read(ADCMUX_INTERNALTEMP);
+ usb_rawhid_send("temp c1101: ",12);
+ write_buffer[0] = '0' + c1101_temp/26;
+ write_buffer[1] = 0;
+ usb_rawhid_send(write_buffer,1);
+ usb_rawhid_send("temp atmega: ",13);
+ write_buffer[0] = '0' + internal_temp/26;
+ usb_rawhid_send(write_buffer,1);
char buf[10];
unsigned int len;
spi_read(sizeof(buf),buf,&len);
diff --git a/software/hhd70dongle/spi.c b/software/hhd70dongle/spi.c
index ab5d5b2..1e2e377 100644
--- a/software/hhd70dongle/spi.c
+++ b/software/hhd70dongle/spi.c
@@ -11,7 +11,7 @@
* Please visit the project hompage at sat.mur.at for further information.
*
*
- * Copyright (C) 2011 Christian Pointner <equinox@mur.at>
+ * Copyright (C) 2012 Bernhard Tittelbach <xro@realraum.at>
*
* This file is part of mur.sat.
*
@@ -51,13 +51,26 @@ void spi_init(void)
DDRB = (1<<DDB0) | (1<<DDB1) | (1<<DDB2);
SPI_PORT = 0;
SPI_DDR = (1<<MOSI)|(1<<SCK)|(1<<CS);
- SPCR = (1<<SPE)|(1<<MSTR);
+ SPCR = (1<<SPE)|(1<<MSTR); // | (0<<DORD) //select MSB first: DORD == 0
// SPSR = (0<<SPI2X) // f_osc/4
// SPSR = (1<<SPI2X) // f_osc/2
// SPSR = (1<<SPI2X); (4MHz vs. 8MHz)
}
+void spi_cs_enable(void)
+{
+ //pull low
+ PORTB &= ~(1<<CS);
+}
+
+void spi_cs_disable(void)
+{
+ //pull high
+ PORTB |= (1<<CS);
+}
+
//synchronous
+//MSB first
void spi_write_byte(char byte)
{
SPDR = byte; //Load byte to Data register
@@ -66,14 +79,15 @@ void spi_write_byte(char byte)
void spi_write(char* data, unsigned int len)
{
- //enable SS of CC1101
- PORTB |= (1<<CS);
-
for (unsigned int c=0; c<len; c++)
spi_write_byte(data[c]);
-
- //disable SS of CC1101
- PORTB &= ~(1<<CS);
+}
+
+//MSB first
+char spi_read_byte(void)
+{
+ while(SPI_PINB_REG & (1<<MISO)); /* wait for CC1101 to get ready... */
+ return SPSR;
}
void spi_read(unsigned int maxlen, char *data, unsigned int *len)
@@ -89,23 +103,189 @@ void spi_read(unsigned int maxlen, char *data, unsigned int *len)
PORTB &= ~(1<<CS);
}
+//read/write config registers:
+#define SPIC1101_ADDR_IOCFG2 0x00
+#define SPIC1101_ADDR_IOCFG1 0x01
+#define SPIC1101_ADDR_IOCFG0 0x02
+#define SPIC1101_ADDR_FIFOTHR 0x03
+#define SPIC1101_ADDR_SYNC1 0x04
+#define SPIC1101_ADDR_SYNC0 0x05
+#define SPIC1101_ADDR_PKTLEN 0x06
+#define SPIC1101_ADDR_PKTCTRL1 0x07
+#define SPIC1101_ADDR_PKTCTRL0 0x08
+#define SPIC1101_ADDR_ADDR 0x09
+#define SPIC1101_ADDR_CHANNR 0x0A
+#define SPIC1101_ADDR_FSCTRL1 0x0B
+#define SPIC1101_ADDR_FSCTRL0 0x0C
+#define SPIC1101_ADDR_FREQ2 0x0D
+#define SPIC1101_ADDR_FREQ1 0x0E
+#define SPIC1101_ADDR_FREQ0 0x0F
+#define SPIC1101_ADDR_MDMCFG4 0x10
+#define SPIC1101_ADDR_MDMCFG3 0x11
+#define SPIC1101_ADDR_MDMCFG2 0x12
+#define SPIC1101_ADDR_MDMCFG1 0x13
+#define SPIC1101_ADDR_MDMCFG0 0x14
+#define SPIC1101_ADDR_DEVIATN 0x15
+#define SPIC1101_ADDR_MCSM2 0x16
+#define SPIC1101_ADDR_MCSM1 0x17
+#define SPIC1101_ADDR_MCSM0 0x18
+#define SPIC1101_ADDR_FOCCFG 0x19
+#define SPIC1101_ADDR_BSCFG 0x1A
+#define SPIC1101_ADDR_AGCCTRL2 0x1B
+#define SPIC1101_ADDR_AGCCTRL1 0x1C
+#define SPIC1101_ADDR_AGCCTRL0 0x1D
+#define SPIC1101_ADDR_WOREVT1 0x1E
+#define SPIC1101_ADDR_WOREVT0 0x1F
+#define SPIC1101_ADDR_WORCTRL 0x20
+#define SPIC1101_ADDR_FREND1 0x21
+#define SPIC1101_ADDR_FREND0 0x22
+#define SPIC1101_ADDR_FSCAL3 0x23
+#define SPIC1101_ADDR_FSCAL2 0x24
+#define SPIC1101_ADDR_FSCAL1 0x25
+#define SPIC1101_ADDR_FSCAL0 0x26
+#define SPIC1101_ADDR_RCCTRL1 0x27
+#define SPIC1101_ADDR_RCCTRL0 0x28
+#define SPIC1101_ADDR_FSTEST 0x29
+#define SPIC1101_ADDR_PTEST 0x2A
+#define SPIC1101_ADDR_AGCTEST 0x2B
+#define SPIC1101_ADDR_TEST2 0x2C
+#define SPIC1101_ADDR_TEST1 0x2D
+#define SPIC1101_ADDR_TEST0 0x2E
+
+//commands:
+#define SPIC1101_ADDR_SRES 0x30
+#define SPIC1101_ADDR_SFSTXON 0x31
+#define SPIC1101_ADDR_SXOFF 0x32
+#define SPIC1101_ADDR_SCAL 0x33
+#define SPIC1101_ADDR_SRX 0x34
+#define SPIC1101_ADDR_STX 0x35
+#define SPIC1101_ADDR_SIDLE 0x36
+#define SPIC1101_ADDR_SWOR 0x38
+#define SPIC1101_ADDR_SPWD 0x39
+#define SPIC1101_ADDR_SFRX 0x3A
+#define SPIC1101_ADDR_SFTX 0x3B
+#define SPIC1101_ADDR_SWORRST 0x3C
+#define SPIC1101_ADDR_SNOP 0x3D
+
+//readonly registers:
+#define SPIC1101_ADDR_PARTNUM (0x30 | 0xC0)
+#define SPIC1101_ADDR_VERSION (0x31 | 0xC0)
+#define SPIC1101_ADDR_FREQUEST (0x32 | 0xC0)
+#define SPIC1101_ADDR_LQI (0x33 | 0xC0)
+#define SPIC1101_ADDR_RSSI (0x34 | 0xC0)
+#define SPIC1101_ADDR_MARCSTATE (0x35 | 0xC0)
+#define SPIC1101_ADDR_WORTIME1 (0x36 | 0xC0)
+#define SPIC1101_ADDR_WORTIME0 (0x37 | 0xC0)
+#define SPIC1101_ADDR_PKTSTATUS (0x38 | 0xC0)
+#define SPIC1101_ADDR_VCO_VC_DAC (0x39 | 0xC0)
+#define SPIC1101_ADDR_TXBYTES (0x3A | 0xC0)
+#define SPIC1101_ADDR_RXBYTES (0x3B | 0xC0)
+#define SPIC1101_ADDR_RCCTRL1_STATUS (0x3C | 0xC0)
+#define SPIC1101_ADDR_RCCTRL0_STATUS (0x3D | 0xC0)
+
+
+#define SPIC1101_ADDR_FIFO_READ (0x3F | 0x80)
+#define SPIC1101_ADDR_FIFO_READ_BURST (0x3F | 0x80 | 0xC0)
+#define SPIC1101_ADDR_FIFO_WRITE 0x3F
+#define SPIC1101_ADDR_FIFO_WRITE_BURST (0x3F | 0x40)
+
+#define SPIC1101_SB_CHIPRDY(x) x & 0b1000000
+#define SPIC1101_SB_IDLE(x) (x & 0b0111000) == 0b000000
+#define SPIC1101_SB_RXMODE(x) (x & 0b0111000) == 0b001000
+#define SPIC1101_SB_TXMODE(x) (x & 0b0111000) == 0b010000
+#define SPIC1101_SB_FSTXON(x) (x & 0b0111000) == 0b011000
+#define SPIC1101_SB_CALIBRATE(x) (x & 0b0111000) == 0b100000
+#define SPIC1101_SB_SETTLING(x) (x & 0b0111000) == 0b101000
+#define SPIC1101_SB_RXFIFO_OVERFLOW(x) (x & 0b0111000b) == 0b110000
+#define SPIC1101_SB_TXFIFO_OVERFLOW(x) (x & 0b0111000b) == 0b111000
+#define SPIC1101_SB_FIFO_BYTES_AVAILABLE(x) (x & 0b0000111)
+
+char spi_c1101_exchange(char *data, int len)
+{
+ char rbyte;
+ spi_cs_enable();
+ while (len--)
+ {
+ while ( ! (SPIC1101_SB_CHIPRDY(spi_read_byte())));
+ spi_write_byte(*(data++));
+ }
+ rbyte = spi_read_byte();
+ spi_cs_disable();
+ return rbyte;
+}
+
+// note addresses range from 0x00 to 0x2F for normal registers and 0xF0 to 0xFD for special status registers
+char spi_c1101_read_register(char address)
+{
+ char data[1];
+ data[0]=address | 0x80;
+ return spi_c1101_exchange(data, 1);
+}
+
+// note addresses range from 0x00 to 0x2F for normal registers
+char spi_c1101_write_register(char address, char byte)
+{
+ char data[2];
+ data[0]=address & 0x2F;
+ data[1]=byte;
+ return spi_c1101_exchange(data, 2);
+}
+
+// note addresses range from 0x30 to 0x3D for command strobes
+char spi_c1101_strobe_command(char address)
+{
+ char data[1];
+ data[0]=address;
+ return spi_c1101_exchange(data, 1);
+}
+
+int spi_c1101_read_rxfifo(int leave_num_bytes, char *buffer, int maxlen)
+{
+ char sb;
+ int num_read = 0;
+ int num_fifo_available = 0;
+ spi_cs_enable();
+ while ( ! (SPIC1101_SB_CHIPRDY(spi_read_byte())));
+ spi_write_byte(SPIC1101_ADDR_FIFO_READ_BURST);
+ do
+ {
+ sb = spi_read_byte();
+ } while ( ! (SPIC1101_SB_CHIPRDY(sb)));
+ num_fifo_available = SPIC1101_SB_FIFO_BYTES_AVAILABLE(sb);
+
+ while (maxlen-- && num_fifo_available - num_read <= leave_num_bytes)
+ {
+ //hope this works !!
+ buffer[num_read++] = spi_read_byte();
+ }
+ spi_cs_disable();
+ return num_read;
+}
-//~ void SPI_interrupt(void) __interrupt (0x0053) __using (1)
-//~ {
- //~ //P1_0=0;
- //~ switch ( SPSCR ) /* read and clear spi status register */
- //~ {
- //~ case 0x80:
- //~ serial_data=SPDAT; /* read receive data */
- //~ transmit_completed=1;/* set software flag */
- //~ break;
-
- //~ case 0x10:
- //~ /* put here for mode fault tasking */
- //~ break;
-
- //~ case 0x40:
- //~ /* put here for overrun tasking */
- //~ break;
- //~ }
-//~ }
+//note: always check if num_written returned == len given
+int spi_c1101_write_txfifo(char *buffer, int len)
+{
+ char sb;
+ int num_written = 0;
+ int num_fifo_available = 0;
+ spi_cs_enable();
+ while ( ! (SPIC1101_SB_CHIPRDY(spi_read_byte())));
+ spi_write_byte(SPIC1101_ADDR_FIFO_WRITE_BURST);
+ do
+ {
+ sb = spi_read_byte();
+ } while ( ! (SPIC1101_SB_CHIPRDY(sb)));
+ num_fifo_available = SPIC1101_SB_FIFO_BYTES_AVAILABLE(sb);
+
+ //if there is less space in tx-fifo than num-byte we want to send, only fill fifo until full and leave rest of buffer unsent (for now)
+ if (num_fifo_available < len)
+ len = num_fifo_available;
+
+ while (len--)
+ {
+ //hope this works !!
+ spi_write_byte(buffer[num_written++]);
+ }
+ spi_cs_disable();
+ return num_written;
+} \ No newline at end of file
diff --git a/software/hhd70dongle/spi.h b/software/hhd70dongle/spi.h
index 6346c05..8d1ac67 100644
--- a/software/hhd70dongle/spi.h
+++ b/software/hhd70dongle/spi.h
@@ -11,7 +11,7 @@
* Please visit the project hompage at sat.mur.at for further information.
*
*
- * Copyright (C) 2011 Christian Pointner <equinox@mur.at>
+ * Copyright (C) 2012 Bernhard Tittelbach <xro@realraum.at>
*
* This file is part of mur.sat.
*