Merge pull request #7788 from he-so/dev-arendst

Jarolift shutter working with keeloq
This commit is contained in:
Theo Arends 2020-02-27 17:37:02 +01:00 committed by GitHub
commit e7f1e0ac3c
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 2149 additions and 2 deletions

12
lib/KeeloqLib/README.md Normal file
View File

@ -0,0 +1,12 @@
## Keeloq encryption algorithm
This implementations might be useful if you are playing around with [Microchip Keeloq](http://www.microchip.com/pagehandler/en-us/technology/embeddedsecurity/technology/keeloqencoderdl.html) chips.
I verified that this algorithm gives the same results as that produced by the Microchip SDK for several test cases.
The Keeloq algorithm is not patented.
However, since Microchip does hold a patent on its application to secure keyless entry,
it probably would not be wise to make a commercial secure keyless entry product using this algorithm in a non-Microchip processor.
Personal experimentation should be okay.
__If you decide to make something commercial, buy Microchip's processors.__

View File

@ -0,0 +1,20 @@
#######################################
# Syntax Coloring Map For CamelliaLib.
#######################################
#######################################
# Datatypes (KEYWORD1)
#######################################
Keeloq KEYWORD1
#######################################
# Methods and Functions (KEYWORD2)
#######################################
encrypt KEYWORD2
decrypt KEYWORD2
#######################################
# Constants (LITERAL1)
#######################################

View File

@ -0,0 +1,9 @@
name=KeeloqLib
version=1.1
author=Mirko Falchetto <mirko.monmarche@gmail.com>
maintainer=Mirko Falchetto <mirko.monmarche@gmail.com>
sentence=C++ Class Implementing Keeloq cipher by Microchip.com.
paragraph=Developed/Tested on Arduino/ESP8266 with Arduino IDE Environment.
category=Uncategorized
url=http://none.net
architectures=*

View File

@ -0,0 +1,58 @@
/*
Keeloq.cpp - Keeloq encryption/decryption
Written by Frank Kienast in November, 2010
*/
#include "KeeloqLib.h"
#define KeeLoq_NLF (0x3A5C742EUL)
Keeloq::Keeloq(const unsigned long keyHigh, const unsigned long keyLow) :
_keyHigh( keyHigh ),
_keyLow( keyLow )
{
}
unsigned long Keeloq::encrypt( const unsigned long data )
{
unsigned long x = data;
unsigned long r;
int keyBitNo, index;
unsigned long keyBitVal,bitVal;
for ( r = 0; r < 528; r++ )
{
keyBitNo = r & 63;
if(keyBitNo < 32)
keyBitVal = bitRead(_keyLow,keyBitNo);
else
keyBitVal = bitRead(_keyHigh, keyBitNo - 32);
index = 1 * bitRead(x,1) + 2 * bitRead(x,9) + 4 * bitRead(x,20) + 8 * bitRead(x,26) + 16 * bitRead(x,31);
bitVal = bitRead(x,0) ^ bitRead(x, 16) ^ bitRead(KeeLoq_NLF,index) ^ keyBitVal;
x = (x>>1) ^ bitVal<<31;
}
return x;
}
unsigned long Keeloq::decrypt( const unsigned long data )
{
unsigned long x = data;
unsigned long r;
int keyBitNo, index;
unsigned long keyBitVal,bitVal;
for (r = 0; r < 528; r++)
{
keyBitNo = (15-r) & 63;
if(keyBitNo < 32)
keyBitVal = bitRead(_keyLow,keyBitNo);
else
keyBitVal = bitRead(_keyHigh, keyBitNo - 32);
index = 1 * bitRead(x,0) + 2 * bitRead(x,8) + 4 * bitRead(x,19) + 8 * bitRead(x,25) + 16 * bitRead(x,30);
bitVal = bitRead(x,31) ^ bitRead(x, 15) ^ bitRead(KeeLoq_NLF,index) ^ keyBitVal;
x = (x<<1) ^ bitVal;
}
return x;
}

View File

@ -0,0 +1,28 @@
/*
Keeloq.h - Crypto library
Written by Frank Kienast in November, 2010
*/
#ifndef Keeloq_lib_h
#define Keeloq_lib_h
#if defined(ARDUINO) && ARDUINO >= 100
#include <Arduino.h>
#else
#include <WProgram.h>
#endif
class Keeloq
{
public:
Keeloq(
const unsigned long keyHigh,
const unsigned long keyLow );
unsigned long encrypt( const unsigned long data );
unsigned long decrypt( const unsigned long data );
private:
unsigned long _keyHigh;
unsigned long _keyLow;
};
#endif /*Keeloq_lib_h*/

View File

@ -0,0 +1,27 @@
#include <KeeloqLib.h>
void setup( void )
{
Serial.begin(9600);
Keeloq k(0x01020304,0x05060708);
const unsigned long p = 6623281UL;
const unsigned long enc = k.encrypt(p);
const unsigned long dec = k.decrypt(enc);
Serial.print("Plaintext : ");
Serial.println(p,DEC);
Serial.print("After encrypt: ");
Serial.println(enc,HEX);
Serial.print("After decrypt: ");
Serial.println(dec,DEC);
}
void loop( void )
{
delay(3000);
}

1
lib/cc1101/README.md Normal file
View File

@ -0,0 +1 @@
Port of panStamp's CC1101 Library to ESP8266.

548
lib/cc1101/cc1101.cpp Normal file
View File

@ -0,0 +1,548 @@
#include <SPI.h>
/**
* Copyright (c) 2011 panStamp <contact@panstamp.com>
*
* This file is part of the panStamp project.
*
* panStamp 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
* any later version.
*
* panStamp is distributed in the hope that 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 panStamp; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301
* USA
*
* Author: Daniel Berenguer
* Creation date: 03/03/2011
*/
extern "C" {
#include "cc1101.h"
}
#define PORT_GDO0 5
#define byte uint8_t
/**
* Macros
*/
// Select (SPI) CC1101
#define cc1101_Select() spi.begin()
// Deselect (SPI) CC1101
#define cc1101_Deselect() spi.end()
// Wait until SPI MISO line goes low
#define wait_Miso() delay(10)
//while(digitalRead(PORT_SPI_MISO))
// Get GDO0 pin state
#define getGDO0state() digitalRead(PORT_GDO0)
// Wait until GDO0 line goes high
#define wait_GDO0_high() while(!getGDO0state()) {delay(1);}
// Wait until GDO0 line goes low
#define wait_GDO0_low() while(getGDO0state()) {delay(1);}
/**
* PATABLE
*/
const byte paTable[8] = {0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00};
/**
* CC1101
*
* Class constructor
*/
CC1101::CC1101(void)
{
carrierFreq = CFREQ_868;
channel = CC1101_DEFVAL_CHANNR;
syncWord[0] = CC1101_DEFVAL_SYNC1;
syncWord[1] = CC1101_DEFVAL_SYNC0;
devAddress = CC1101_DEFVAL_ADDR;
paTableByte = PA_LowPower; // Priority = Low power
}
/**
* wakeUp
*
* Wake up CC1101 from Power Down state
*/
void CC1101::wakeUp(void)
{
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
cc1101_Deselect(); // Deselect CC1101
}
/**
* writeReg
*
* Write single register into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'value' Value to be writen
*/
void CC1101::writeReg(byte regAddr, byte value)
{
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(regAddr); // Send register address
spi.transfer(value); // Send value
cc1101_Deselect(); // Deselect CC1101
}
/**
* writeBurstReg
*
* Write multiple registers into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'buffer' Data to be writen
* 'len' Data length
*/
void CC1101::writeBurstReg(byte regAddr, byte* buffer, byte len)
{
byte addr, i;
addr = regAddr | WRITE_BURST; // Enable burst transfer
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(addr); // Send register address
for(i=0 ; i<len ; i++)
spi.transfer(buffer[i]); // Send value
cc1101_Deselect(); // Deselect CC1101
}
/**
* cmdStrobe
*
* Send command strobe to the CC1101 IC via SPI
*
* 'cmd' Command strobe
*/
void CC1101::cmdStrobe(byte cmd)
{
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(cmd); // Send strobe command
cc1101_Deselect(); // Deselect CC1101
}
/**
* readReg
*
* Read CC1101 register via SPI
*
* 'regAddr' Register address
* 'regType' Type of register: CC1101_CONFIG_REGISTER or CC1101_STATUS_REGISTER
*
* Return:
* Data byte returned by the CC1101 IC
*/
byte CC1101::readReg(byte regAddr, byte regType)
{
byte addr, val;
addr = regAddr | regType;
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(addr); // Send register address
val = spi.transfer(0x00); // Read result
cc1101_Deselect(); // Deselect CC1101
return val;
}
/**
* readBurstReg
*
* Read burst data from CC1101 via SPI
*
* 'buffer' Buffer where to copy the result to
* 'regAddr' Register address
* 'len' Data length
*/
void CC1101::readBurstReg(byte * buffer, byte regAddr, byte len)
{
byte addr, i;
addr = regAddr | READ_BURST;
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(addr); // Send register address
for(i=0 ; i<len ; i++)
buffer[i] = spi.transfer(0x00); // Read result byte by byte
cc1101_Deselect(); // Deselect CC1101
}
/**
* reset
*
* Reset CC1101
*/
void CC1101::reset(void)
{
cc1101_Deselect(); // Deselect CC1101
delayMicroseconds(5);
cc1101_Select(); // Select CC1101
delayMicroseconds(10);
cc1101_Deselect(); // Deselect CC1101
delayMicroseconds(41);
cc1101_Select(); // Select CC1101
wait_Miso(); // Wait until MISO goes low
spi.transfer(CC1101_SRES); // Send reset command strobe
wait_Miso(); // Wait until MISO goes low
cc1101_Deselect(); // Deselect CC1101
setCCregs(); // Reconfigure CC1101
}
/**
* setCCregs
*
* Configure CC1101 registers
*/
void CC1101::setCCregs(void)
{
writeReg(CC1101_IOCFG2, CC1101_DEFVAL_IOCFG2);
writeReg(CC1101_IOCFG1, CC1101_DEFVAL_IOCFG1);
writeReg(CC1101_IOCFG0, CC1101_DEFVAL_IOCFG0);
writeReg(CC1101_FIFOTHR, CC1101_DEFVAL_FIFOTHR);
writeReg(CC1101_PKTLEN, CC1101_DEFVAL_PKTLEN);
writeReg(CC1101_PKTCTRL1, CC1101_DEFVAL_PKTCTRL1);
writeReg(CC1101_PKTCTRL0, CC1101_DEFVAL_PKTCTRL0);
// Set default synchronization word
setSyncWord(syncWord);
// Set default device address
setDevAddress(devAddress);
// Set default frequency channel
setChannel(channel);
writeReg(CC1101_FSCTRL1, CC1101_DEFVAL_FSCTRL1);
writeReg(CC1101_FSCTRL0, CC1101_DEFVAL_FSCTRL0);
// Set default carrier frequency = 868 MHz
setCarrierFreq(carrierFreq);
writeReg(CC1101_MDMCFG4, CC1101_DEFVAL_MDMCFG4);
writeReg(CC1101_MDMCFG3, CC1101_DEFVAL_MDMCFG3);
writeReg(CC1101_MDMCFG2, CC1101_DEFVAL_MDMCFG2);
writeReg(CC1101_MDMCFG1, CC1101_DEFVAL_MDMCFG1);
writeReg(CC1101_MDMCFG0, CC1101_DEFVAL_MDMCFG0);
writeReg(CC1101_DEVIATN, CC1101_DEFVAL_DEVIATN);
writeReg(CC1101_MCSM2, CC1101_DEFVAL_MCSM2);
writeReg(CC1101_MCSM1, CC1101_DEFVAL_MCSM1);
writeReg(CC1101_MCSM0, CC1101_DEFVAL_MCSM0);
writeReg(CC1101_FOCCFG, CC1101_DEFVAL_FOCCFG);
writeReg(CC1101_BSCFG, CC1101_DEFVAL_BSCFG);
writeReg(CC1101_AGCCTRL2, CC1101_DEFVAL_AGCCTRL2);
writeReg(CC1101_AGCCTRL1, CC1101_DEFVAL_AGCCTRL1);
writeReg(CC1101_AGCCTRL0, CC1101_DEFVAL_AGCCTRL0);
writeReg(CC1101_WOREVT1, CC1101_DEFVAL_WOREVT1);
writeReg(CC1101_WOREVT0, CC1101_DEFVAL_WOREVT0);
writeReg(CC1101_WORCTRL, CC1101_DEFVAL_WORCTRL);
writeReg(CC1101_FREND1, CC1101_DEFVAL_FREND1);
writeReg(CC1101_FREND0, CC1101_DEFVAL_FREND0);
writeReg(CC1101_FSCAL3, CC1101_DEFVAL_FSCAL3);
writeReg(CC1101_FSCAL2, CC1101_DEFVAL_FSCAL2);
writeReg(CC1101_FSCAL1, CC1101_DEFVAL_FSCAL1);
writeReg(CC1101_FSCAL0, CC1101_DEFVAL_FSCAL0);
writeReg(CC1101_RCCTRL1, CC1101_DEFVAL_RCCTRL1);
writeReg(CC1101_RCCTRL0, CC1101_DEFVAL_RCCTRL0);
writeReg(CC1101_FSTEST, CC1101_DEFVAL_FSTEST);
writeReg(CC1101_PTEST, CC1101_DEFVAL_PTEST);
writeReg(CC1101_AGCTEST, CC1101_DEFVAL_AGCTEST);
writeReg(CC1101_TEST2, CC1101_DEFVAL_TEST2);
writeReg(CC1101_TEST1, CC1101_DEFVAL_TEST1);
writeReg(CC1101_TEST0, CC1101_DEFVAL_TEST0);
// Send empty packet
CCPACKET packet;
packet.length = 0;
sendData(packet);
}
/**
* init
*
* Initialize CC1101 radio
*
* @param freq Carrier frequency
*/
void CC1101::init(uint8_t freq)
{
carrierFreq = freq;
spi.begin(); // Initialize SPI interface
pinMode(PORT_GDO0, INPUT); // Config GDO0 as input
reset(); // Reset CC1101
// Configure PATABLE
//writeBurstReg(CC1101_PATABLE, (byte*)paTable, 8);
writeReg(CC1101_PATABLE, paTableByte);
}
/**
* setSyncWord
*
* Set synchronization word
*
* 'syncH' Synchronization word - High byte
* 'syncL' Synchronization word - Low byte
*/
void CC1101::setSyncWord(uint8_t syncH, uint8_t syncL)
{
writeReg(CC1101_SYNC1, syncH);
writeReg(CC1101_SYNC0, syncL);
syncWord[0] = syncH;
syncWord[1] = syncL;
}
/**
* setSyncWord (overriding method)
*
* Set synchronization word
*
* 'syncH' Synchronization word - pointer to 2-byte array
*/
void CC1101::setSyncWord(byte *sync)
{
CC1101::setSyncWord(sync[0], sync[1]);
}
/**
* setDevAddress
*
* Set device address
*
* @param addr Device address
*/
void CC1101::setDevAddress(byte addr)
{
writeReg(CC1101_ADDR, addr);
devAddress = addr;
}
/**
* setChannel
*
* Set frequency channel
*
* 'chnl' Frequency channel
*/
void CC1101::setChannel(byte chnl)
{
writeReg(CC1101_CHANNR, chnl);
channel = chnl;
}
/**
* setCarrierFreq
*
* Set carrier frequency
*
* 'freq' New carrier frequency
*/
void CC1101::setCarrierFreq(byte freq)
{
switch(freq)
{
case CFREQ_915:
writeReg(CC1101_FREQ2, CC1101_DEFVAL_FREQ2_915);
writeReg(CC1101_FREQ1, CC1101_DEFVAL_FREQ1_915);
writeReg(CC1101_FREQ0, CC1101_DEFVAL_FREQ0_915);
break;
case CFREQ_433:
writeReg(CC1101_FREQ2, CC1101_DEFVAL_FREQ2_433);
writeReg(CC1101_FREQ1, CC1101_DEFVAL_FREQ1_433);
writeReg(CC1101_FREQ0, CC1101_DEFVAL_FREQ0_433);
break;
case CFREQ_918:
writeReg(CC1101_FREQ2, CC1101_DEFVAL_FREQ2_918);
writeReg(CC1101_FREQ1, CC1101_DEFVAL_FREQ1_918);
writeReg(CC1101_FREQ0, CC1101_DEFVAL_FREQ0_918);
break;
default:
writeReg(CC1101_FREQ2, CC1101_DEFVAL_FREQ2_868);
writeReg(CC1101_FREQ1, CC1101_DEFVAL_FREQ1_868);
writeReg(CC1101_FREQ0, CC1101_DEFVAL_FREQ0_868);
break;
}
carrierFreq = freq;
}
/**
* setPowerDownState
*
* Put CC1101 into power-down state
*/
void CC1101::setPowerDownState()
{
// Comming from RX state, we need to enter the IDLE state first
cmdStrobe(CC1101_SIDLE);
// Enter Power-down state
cmdStrobe(CC1101_SPWD);
}
/**
* sendData
*
* Send data packet via RF
*
* 'packet' Packet to be transmitted. First byte is the destination address
*
* Return:
* True if the transmission succeeds
* False otherwise
*/
bool CC1101::sendData(CCPACKET packet)
{
byte marcState;
bool res = false;
// Declare to be in Tx state. This will avoid receiving packets whilst
// transmitting
rfState = RFSTATE_TX;
// Enter RX state
setRxState();
// Check that the RX state has been entered
while (((marcState = readStatusReg(CC1101_MARCSTATE)) & 0x1F) != 0x0D)
{
if (marcState == 0x11) // RX_OVERFLOW
flushRxFifo(); // flush receive queue
}
delayMicroseconds(500);
if (packet.length > 0)
{
// Set data length at the first position of the TX FIFO
writeReg(CC1101_TXFIFO, packet.length);
// Write data into the TX FIFO
writeBurstReg(CC1101_TXFIFO, packet.data, packet.length);
// CCA enabled: will enter TX state only if the channel is clear
setTxState();
}
// Check that TX state is being entered (state = RXTX_SETTLING)
marcState = readStatusReg(CC1101_MARCSTATE) & 0x1F;
if((marcState != 0x13) && (marcState != 0x14) && (marcState != 0x15))
{
setIdleState(); // Enter IDLE state
flushTxFifo(); // Flush Tx FIFO
setRxState(); // Back to RX state
// Declare to be in Rx state
rfState = RFSTATE_RX;
return false;
}
// Wait for the sync word to be transmitted
wait_GDO0_high();
// Wait until the end of the packet transmission
wait_GDO0_low();
// Check that the TX FIFO is empty
if((readStatusReg(CC1101_TXBYTES) & 0x7F) == 0)
res = true;
setIdleState(); // Enter IDLE state
flushTxFifo(); // Flush Tx FIFO
// Enter back into RX state
setRxState();
// Declare to be in Rx state
rfState = RFSTATE_RX;
return res;
}
/**
* receiveData
*
* Read data packet from RX FIFO
*
* 'packet' Container for the packet received
*
* Return:
* Amount of bytes received
*/
byte CC1101::receiveData(CCPACKET * packet)
{
byte val;
byte rxBytes = readStatusReg(CC1101_RXBYTES);
// Any byte waiting to be read and no overflow?
if (rxBytes & 0x7F)
{
// Read data length
packet->length = readConfigReg(CC1101_RXFIFO);
// If packet is too long
if (packet->length > CCPACKET_DATA_LEN)
packet->length = 0; // Discard packet
else
{
// Read data packet
readBurstReg(packet->data, CC1101_RXFIFO, packet->length);
// Read RSSI
packet->rssi = readConfigReg(CC1101_RXFIFO);
// Read LQI and CRC_OK
val = readConfigReg(CC1101_RXFIFO);
packet->lqi = val & 0x7F;
packet->crc_ok = bitRead(val, 7);
}
}
else
packet->length = 0;
setIdleState(); // Enter IDLE state
flushRxFifo(); // Flush Rx FIFO
//cmdStrobe(CC1101_SCAL);
// Back to RX state
setRxState();
return packet->length;
}
/**
* setRxState
*
* Enter Rx state
*/
void CC1101::setRxState(void)
{
cmdStrobe(CC1101_SRX);
rfState = RFSTATE_RX;
}
/**
* setTxState
*
* Enter Tx state
*/
void CC1101::setTxState(void)
{
cmdStrobe(CC1101_STX);
rfState = RFSTATE_TX;
}

548
lib/cc1101/cc1101.h Normal file
View File

@ -0,0 +1,548 @@
#include <SPI.h>
/**
* Copyright (c) 2011 panStamp <contact@panstamp.com>
*
* This file is part of the panStamp project.
*
* panStamp 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
* any later version.
*
* panStamp is distributed in the hope that 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 panStamp; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301
* USA
*
* Author: Daniel Berenguer
* Creation date: 03/03/2011
*/
#ifndef _CC1101_H
#define _CC1101_H
//#include "simplespi.h"
extern "C" {
#include <stdint.h>
#include "ccpacket.h"
}
/**
* Carrier frequencies
*/
enum CFREQ
{
CFREQ_868 = 0,
CFREQ_915,
CFREQ_433,
CFREQ_918,
CFREQ_LAST
};
/**
* RF STATES
*/
enum RFSTATE
{
RFSTATE_IDLE = 0,
RFSTATE_RX,
RFSTATE_TX
};
/**
* Frequency channels
*/
#define NUMBER_OF_FCHANNELS 10
/**
* Type of transfers
*/
#define WRITE_BURST 0x40
#define READ_SINGLE 0x80
#define READ_BURST 0xC0
/**
* Type of register
*/
#define CC1101_CONFIG_REGISTER READ_SINGLE
#define CC1101_STATUS_REGISTER READ_BURST
/**
* PATABLE & FIFO's
*/
#define CC1101_PATABLE 0x3E // PATABLE address
#define CC1101_TXFIFO 0x3F // TX FIFO address
#define CC1101_RXFIFO 0x3F // RX FIFO address
/**
* Command strobes
*/
#define CC1101_SRES 0x30 // Reset CC1101 chip
#define CC1101_SFSTXON 0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). If in RX (with CCA):
// Go to a wait state where only the synthesizer is running (for quick RX / TX turnaround).
#define CC1101_SXOFF 0x32 // Turn off crystal oscillator
#define CC1101_SCAL 0x33 // Calibrate frequency synthesizer and turn it off. SCAL can be strobed from IDLE mode without
// setting manual calibration mode (MCSM0.FS_AUTOCAL=0)
#define CC1101_SRX 0x34 // Enable RX. Perform calibration first if coming from IDLE and MCSM0.FS_AUTOCAL=1
#define CC1101_STX 0x35 // In IDLE state: Enable TX. Perform calibration first if MCSM0.FS_AUTOCAL=1.
// If in RX state and CCA is enabled: Only go to TX if channel is clear
#define CC1101_SIDLE 0x36 // Exit RX / TX, turn off frequency synthesizer and exit Wake-On-Radio mode if applicable
#define CC1101_SWOR 0x38 // Start automatic RX polling sequence (Wake-on-Radio) as described in Section 19.5 if
// WORCTRL.RC_PD=0
#define CC1101_SPWD 0x39 // Enter power down mode when CSn goes high
#define CC1101_SFRX 0x3A // Flush the RX FIFO buffer. Only issue SFRX in IDLE or RXFIFO_OVERFLOW states
#define CC1101_SFTX 0x3B // Flush the TX FIFO buffer. Only issue SFTX in IDLE or TXFIFO_UNDERFLOW states
#define CC1101_SWORRST 0x3C // Reset real time clock to Event1 value
#define CC1101_SNOP 0x3D // No operation. May be used to get access to the chip status byte
/**
* CC1101 configuration registers
*/
#define CC1101_IOCFG2 0x00 // GDO2 Output Pin Configuration
#define CC1101_IOCFG1 0x01 // GDO1 Output Pin Configuration
#define CC1101_IOCFG0 0x02 // GDO0 Output Pin Configuration
#define CC1101_FIFOTHR 0x03 // RX FIFO and TX FIFO Thresholds
#define CC1101_SYNC1 0x04 // Sync Word, High Byte
#define CC1101_SYNC0 0x05 // Sync Word, Low Byte
#define CC1101_PKTLEN 0x06 // Packet Length
#define CC1101_PKTCTRL1 0x07 // Packet Automation Control
#define CC1101_PKTCTRL0 0x08 // Packet Automation Control
#define CC1101_ADDR 0x09 // Device Address
#define CC1101_CHANNR 0x0A // Channel Number
#define CC1101_FSCTRL1 0x0B // Frequency Synthesizer Control
#define CC1101_FSCTRL0 0x0C // Frequency Synthesizer Control
#define CC1101_FREQ2 0x0D // Frequency Control Word, High Byte
#define CC1101_FREQ1 0x0E // Frequency Control Word, Middle Byte
#define CC1101_FREQ0 0x0F // Frequency Control Word, Low Byte
#define CC1101_MDMCFG4 0x10 // Modem Configuration
#define CC1101_MDMCFG3 0x11 // Modem Configuration
#define CC1101_MDMCFG2 0x12 // Modem Configuration
#define CC1101_MDMCFG1 0x13 // Modem Configuration
#define CC1101_MDMCFG0 0x14 // Modem Configuration
#define CC1101_DEVIATN 0x15 // Modem Deviation Setting
#define CC1101_MCSM2 0x16 // Main Radio Control State Machine Configuration
#define CC1101_MCSM1 0x17 // Main Radio Control State Machine Configuration
#define CC1101_MCSM0 0x18 // Main Radio Control State Machine Configuration
#define CC1101_FOCCFG 0x19 // Frequency Offset Compensation Configuration
#define CC1101_BSCFG 0x1A // Bit Synchronization Configuration
#define CC1101_AGCCTRL2 0x1B // AGC Control
#define CC1101_AGCCTRL1 0x1C // AGC Control
#define CC1101_AGCCTRL0 0x1D // AGC Control
#define CC1101_WOREVT1 0x1E // High Byte Event0 Timeout
#define CC1101_WOREVT0 0x1F // Low Byte Event0 Timeout
#define CC1101_WORCTRL 0x20 // Wake On Radio Control
#define CC1101_FREND1 0x21 // Front End RX Configuration
#define CC1101_FREND0 0x22 // Front End TX Configuration
#define CC1101_FSCAL3 0x23 // Frequency Synthesizer Calibration
#define CC1101_FSCAL2 0x24 // Frequency Synthesizer Calibration
#define CC1101_FSCAL1 0x25 // Frequency Synthesizer Calibration
#define CC1101_FSCAL0 0x26 // Frequency Synthesizer Calibration
#define CC1101_RCCTRL1 0x27 // RC Oscillator Configuration
#define CC1101_RCCTRL0 0x28 // RC Oscillator Configuration
#define CC1101_FSTEST 0x29 // Frequency Synthesizer Calibration Control
#define CC1101_PTEST 0x2A // Production Test
#define CC1101_AGCTEST 0x2B // AGC Test
#define CC1101_TEST2 0x2C // Various Test Settings
#define CC1101_TEST1 0x2D // Various Test Settings
#define CC1101_TEST0 0x2E // Various Test Settings
/**
* Status registers
*/
#define CC1101_PARTNUM 0x30 // Chip ID
#define CC1101_VERSION 0x31 // Chip ID
#define CC1101_FREQEST 0x32 // Frequency Offset Estimate from Demodulator
#define CC1101_LQI 0x33 // Demodulator Estimate for Link Quality
#define CC1101_RSSI 0x34 // Received Signal Strength Indication
#define CC1101_MARCSTATE 0x35 // Main Radio Control State Machine State
#define CC1101_WORTIME1 0x36 // High Byte of WOR Time
#define CC1101_WORTIME0 0x37 // Low Byte of WOR Time
#define CC1101_PKTSTATUS 0x38 // Current GDOx Status and Packet Status
#define CC1101_VCO_VC_DAC 0x39 // Current Setting from PLL Calibration Module
#define CC1101_TXBYTES 0x3A // Underflow and Number of Bytes
#define CC1101_RXBYTES 0x3B // Overflow and Number of Bytes
#define CC1101_RCCTRL1_STATUS 0x3C // Last RC Oscillator Calibration Result
#define CC1101_RCCTRL0_STATUS 0x3D // Last RC Oscillator Calibration Result
/**
* CC1101 configuration registers - Default values extracted from SmartRF Studio
*
* Configuration:
*
* Deviation = 20.629883
* Base frequency = 867.999939
* Carrier frequency = 867.999939
* Channel number = 0
* Carrier frequency = 867.999939
* Modulated = true
* Modulation format = GFSK
* Manchester enable = false
* Data whitening = off
* Sync word qualifier mode = 30/32 sync word bits detected
* Preamble count = 4
* Channel spacing = 199.951172
* Carrier frequency = 867.999939
* Data rate = 38.3835 Kbps
* RX filter BW = 101.562500
* Data format = Normal mode
* Length config = Variable packet length mode. Packet length configured by the first byte after sync word
* CRC enable = true
* Packet length = 255
* Device address = 1
* Address config = Enable address check
* Append status = Append two status bytes to the payload of the packet. The status bytes contain RSSI and
* LQI values, as well as CRC OK
* CRC autoflush = false
* PA ramping = false
* TX power = 12
* GDO0 mode = Asserts when sync word has been sent / received, and de-asserts at the end of the packet.
* In RX, the pin will also de-assert when a packet is discarded due to address or maximum length filtering
* or when the radio enters RXFIFO_OVERFLOW state. In TX the pin will de-assert if the TX FIFO underflows
* Settings optimized for low current consumption
*/
#define CC1101_DEFVAL_IOCFG2 0x0D // GDO2 Output Pin Configuration
#define CC1101_DEFVAL_IOCFG1 0x2E // GDO1 Output Pin Configuration
#define CC1101_DEFVAL_IOCFG0 0x2D // GDO0 Output Pin Configuration
#define CC1101_DEFVAL_FIFOTHR 0x07 // RX FIFO and TX FIFO Thresholds
#define CC1101_DEFVAL_SYNC1 0xD3 // Synchronization word, high byte
#define CC1101_DEFVAL_SYNC0 0x91 // Synchronization word, low byte
#define CC1101_DEFVAL_PKTLEN 0x3D // Packet Length
#define CC1101_DEFVAL_PKTCTRL1 0x04 // Packet Automation Control
#define CC1101_DEFVAL_PKTCTRL0 0x32 // Packet Automation Control
#define CC1101_DEFVAL_ADDR 0xFF // Device Address
#define CC1101_DEFVAL_CHANNR 0x00 // Channel Number
#define CC1101_DEFVAL_FSCTRL1 0x06 // Frequency Synthesizer Control
#define CC1101_DEFVAL_FSCTRL0 0x00 // Frequency Synthesizer Control
// Carrier frequency = 868 MHz
#define CC1101_DEFVAL_FREQ2_868 0x21 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_868 0x62 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_868 0x76 // Frequency Control Word, Low Byte
// Carrier frequency = 902 MHz
#define CC1101_DEFVAL_FREQ2_915 0x22 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_915 0xB1 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_915 0x3B // Frequency Control Word, Low Byte
// Carrier frequency = 918 MHz
#define CC1101_DEFVAL_FREQ2_918 0x23 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_918 0x4E // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_918 0xC4 // Frequency Control Word, Low Byte
// Carrier frequency = 433 MHz
#define CC1101_DEFVAL_FREQ2_433 0x10 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_433 0xB0 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_433 0xBD // Frequency Control Word, Low Byte
#define CC1101_DEFVAL_MDMCFG4 0x56 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG3 0x83 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG2 0x30 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG1 0x22 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG0 0xF8 // Modem Configuration
#define CC1101_DEFVAL_DEVIATN 0x00 // Modem Deviation Setting
#define CC1101_DEFVAL_MCSM2 0x07 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_MCSM1 0x00 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_MCSM0 0x18 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_FOCCFG 0x14 // Frequency Offset Compensation Configuration
#define CC1101_DEFVAL_BSCFG 0x6C // Bit Synchronization Configuration
#define CC1101_DEFVAL_AGCCTRL2 0x07 // AGC Control
#define CC1101_DEFVAL_AGCCTRL1 0x00 // AGC Control
#define CC1101_DEFVAL_AGCCTRL0 0x91 // AGC Control
#define CC1101_DEFVAL_WOREVT1 0x87 // High Byte Event0 Timeout
#define CC1101_DEFVAL_WOREVT0 0x6B // Low Byte Event0 Timeout
#define CC1101_DEFVAL_WORCTRL 0xF8 // Wake On Radio Control
#define CC1101_DEFVAL_FREND1 0x56 // Front End RX Configuration
#define CC1101_DEFVAL_FREND0 0x11 // Front End TX Configuration
#define CC1101_DEFVAL_FSCAL3 0xE9 // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL2 0x2A // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL1 0x00 // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL0 0x1F // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_RCCTRL1 0x41 // RC Oscillator Configuration
#define CC1101_DEFVAL_RCCTRL0 0x00 // RC Oscillator Configuration
#define CC1101_DEFVAL_FSTEST 0x59 // Frequency Synthesizer Calibration Control
#define CC1101_DEFVAL_PTEST 0x7F // Production Test
#define CC1101_DEFVAL_AGCTEST 0x3F // AGC Test
#define CC1101_DEFVAL_TEST2 0x88 // Various Test Settings
#define CC1101_DEFVAL_TEST1 0x31 // Various Test Settings
#define CC1101_DEFVAL_TEST0 0x09 // Various Test Settings
/**
* Alias for some default values
*/
#define CCDEF_CHANNR CC1101_DEFVAL_CHANNR
#define CCDEF_SYNC0 CC1101_DEFVAL_SYNC0
#define CCDEF_SYNC1 CC1101_DEFVAL_SYNC1
#define CCDEF_ADDR CC1101_DEFVAL_ADDR
/**
* Macros
*/
// Read CC1101 Config register
#define readConfigReg(regAddr) readReg(regAddr, CC1101_CONFIG_REGISTER)
// Read CC1101 Status register
#define readStatusReg(regAddr) readReg(regAddr, CC1101_STATUS_REGISTER)
// Enter Rx state
//#define setRxState() cmdStrobe(CC1101_SRX)
// Enter Tx state
//#define setTxState() cmdStrobe(CC1101_STX)
// Enter IDLE state
#define setIdleState() cmdStrobe(CC1101_SIDLE)
// Flush Rx FIFO
#define flushRxFifo() cmdStrobe(CC1101_SFRX)
// Flush Tx FIFO
#define flushTxFifo() cmdStrobe(CC1101_SFTX)
// Disable address check
#define disableAddressCheck() writeReg(CC1101_PKTCTRL1, 0x04)
// Enable address check
#define enableAddressCheck() writeReg(CC1101_PKTCTRL1, 0x06)
// Disable CCA
#define disableCCA() writeReg(CC1101_MCSM1, 0)
// Enable CCA
#define enableCCA() writeReg(CC1101_MCSM1, CC1101_DEFVAL_MCSM1)
// Set PATABLE single byte
#define setTxPowerAmp(setting) paTableByte = setting
// PATABLE values
#define PA_LowPower 0x60
#define PA_LongDistance 0xC0
/**
* Class: CC1101
*
* Description:
* CC1101 interface
*/
class CC1101
{
private:
/**
* Atmega's SPI interface
*/
SPIClass spi;
/**
* writeBurstReg
*
* Write multiple registers into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'buffer' Data to be writen
* 'len' Data length
*/
void writeBurstReg(uint8_t regAddr, uint8_t* buffer, uint8_t len);
/**
* readBurstReg
*
* Read burst data from CC1101 via SPI
*
* 'buffer' Buffer where to copy the result to
* 'regAddr' Register address
* 'len' Data length
*/
void readBurstReg(uint8_t * buffer, uint8_t regAddr, uint8_t len);
/**
* setRegsFromEeprom
*
* Set registers from EEPROM
*/
void setRegsFromEeprom(void);
public:
/*
* RF state
*/
uint8_t rfState;
/**
* Tx Power byte (single PATABLE config)
*/
uint8_t paTableByte;
/**
* Carrier frequency
*/
uint8_t carrierFreq;
/**
* Frequency channel
*/
uint8_t channel;
/**
* Synchronization word
*/
uint8_t syncWord[2];
/**
* Device address
*/
uint8_t devAddress;
/**
* CC1101
*
* Class constructor
*/
CC1101(void);
/**
* cmdStrobe
*
* Send command strobe to the CC1101 IC via SPI
*
* 'cmd' Command strobe
*/
void cmdStrobe(uint8_t cmd);
/**
* wakeUp
*
* Wake up CC1101 from Power Down state
*/
void wakeUp(void);
/**
* readReg
*
* Read CC1101 register via SPI
*
* 'regAddr' Register address
* 'regType' Type of register: CC1101_CONFIG_REGISTER or CC1101_STATUS_REGISTER
*
* Return:
* Data byte returned by the CC1101 IC
*/
uint8_t readReg(uint8_t regAddr, uint8_t regType);
/**
* writeReg
*
* Write single register into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'value' Value to be writen
*/
void writeReg(uint8_t regAddr, uint8_t value);
/**
* setCCregs
*
* Configure CC1101 registers
*/
void setCCregs(void);
/**
* reset
*
* Reset CC1101
*/
void reset(void);
/**
* init
*
* Initialize CC1101 radio
*
* @param freq Carrier frequency
*/
void init(uint8_t freq=CFREQ_868);
/**
* setSyncWord
*
* Set synchronization word
*
* 'syncH' Synchronization word - High byte
* 'syncL' Synchronization word - Low byte
*/
void setSyncWord(uint8_t syncH, uint8_t syncL);
/**
* setSyncWord (overriding method)
*
* Set synchronization word
*
* 'syncH' Synchronization word - pointer to 2-byte array
*/
void setSyncWord(uint8_t *sync);
/**
* setDevAddress
*
* Set device address
*
* 'addr' Device address
*/
void setDevAddress(uint8_t addr);
/**
* setCarrierFreq
*
* Set carrier frequency
*
* 'freq' New carrier frequency
*/
void setCarrierFreq(uint8_t freq);
/**
* setChannel
*
* Set frequency channel
*
* 'chnl' Frequency channel
*/
void setChannel(uint8_t chnl);
/**
* setPowerDownState
*
* Put CC1101 into power-down state
*/
void setPowerDownState();
/**
* sendData
*
* Send data packet via RF
*
* 'packet' Packet to be transmitted. First byte is the destination address
*
* Return:
* True if the transmission succeeds
* False otherwise
*/
bool sendData(CCPACKET packet);
/**
* receiveData
*
* Read data packet from RX FIFO
*
* Return:
* Amount of bytes received
*/
uint8_t receiveData(CCPACKET *packet);
/**
* setRxState
*
* Enter Rx state
*/
void setRxState(void);
/**
* setTxState
*
* Enter Tx state
*/
void setTxState(void);
};
#endif

549
lib/cc1101/cc1101.h.txt Normal file
View File

@ -0,0 +1,549 @@
#include <SPI.h>
/**
* Copyright (c) 2011 panStamp <contact@panstamp.com>
*
* This file is part of the panStamp project.
*
* panStamp 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
* any later version.
*
* panStamp is distributed in the hope that 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 panStamp; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301
* USA
*
* Author: Daniel Berenguer
* Creation date: 03/03/2011
*/
#ifndef _CC1101_H
#define _CC1101_H
//#include "simplespi.h"
extern "C" {
#include <stdint.h>
#include "ccpacket.h"
}
/**
* Carrier frequencies
*/
enum CFREQ
{
CFREQ_868 = 0,
CFREQ_915,
CFREQ_433,
CFREQ_918,
CFREQ_LAST
};
/**
* RF STATES
*/
enum RFSTATE
{
RFSTATE_IDLE = 0,
RFSTATE_RX,
RFSTATE_TX
};
/**
* Frequency channels
*/
#define NUMBER_OF_FCHANNELS 10
/**
* Type of transfers
*/
#define WRITE_BURST 0x40
#define READ_SINGLE 0x80
#define READ_BURST 0xC0
/**
* Type of register
*/
#define CC1101_CONFIG_REGISTER READ_SINGLE
#define CC1101_STATUS_REGISTER READ_BURST
/**
* PATABLE & FIFO's
*/
#define CC1101_PATABLE 0x3E // PATABLE address
#define CC1101_TXFIFO 0x3F // TX FIFO address
#define CC1101_RXFIFO 0x3F // RX FIFO address
/**
* Command strobes
*/
#define CC1101_SRES 0x30 // Reset CC1101 chip
#define CC1101_SFSTXON 0x31 // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1). If in RX (with CCA):
// Go to a wait state where only the synthesizer is running (for quick RX / TX turnaround).
#define CC1101_SXOFF 0x32 // Turn off crystal oscillator
#define CC1101_SCAL 0x33 // Calibrate frequency synthesizer and turn it off. SCAL can be strobed from IDLE mode without
// setting manual calibration mode (MCSM0.FS_AUTOCAL=0)
#define CC1101_SRX 0x34 // Enable RX. Perform calibration first if coming from IDLE and MCSM0.FS_AUTOCAL=1
#define CC1101_STX 0x35 // In IDLE state: Enable TX. Perform calibration first if MCSM0.FS_AUTOCAL=1.
// If in RX state and CCA is enabled: Only go to TX if channel is clear
#define CC1101_SIDLE 0x36 // Exit RX / TX, turn off frequency synthesizer and exit Wake-On-Radio mode if applicable
#define CC1101_SWOR 0x38 // Start automatic RX polling sequence (Wake-on-Radio) as described in Section 19.5 if
// WORCTRL.RC_PD=0
#define CC1101_SPWD 0x39 // Enter power down mode when CSn goes high
#define CC1101_SFRX 0x3A // Flush the RX FIFO buffer. Only issue SFRX in IDLE or RXFIFO_OVERFLOW states
#define CC1101_SFTX 0x3B // Flush the TX FIFO buffer. Only issue SFTX in IDLE or TXFIFO_UNDERFLOW states
#define CC1101_SWORRST 0x3C // Reset real time clock to Event1 value
#define CC1101_SNOP 0x3D // No operation. May be used to get access to the chip status byte
/**
* CC1101 configuration registers
*/
#define CC1101_IOCFG2 0x00 // GDO2 Output Pin Configuration
#define CC1101_IOCFG1 0x01 // GDO1 Output Pin Configuration
#define CC1101_IOCFG0 0x02 // GDO0 Output Pin Configuration
#define CC1101_FIFOTHR 0x03 // RX FIFO and TX FIFO Thresholds
#define CC1101_SYNC1 0x04 // Sync Word, High Byte
#define CC1101_SYNC0 0x05 // Sync Word, Low Byte
#define CC1101_PKTLEN 0x06 // Packet Length
#define CC1101_PKTCTRL1 0x07 // Packet Automation Control
#define CC1101_PKTCTRL0 0x08 // Packet Automation Control
#define CC1101_ADDR 0x09 // Device Address
#define CC1101_CHANNR 0x0A // Channel Number
#define CC1101_FSCTRL1 0x0B // Frequency Synthesizer Control
#define CC1101_FSCTRL0 0x0C // Frequency Synthesizer Control
#define CC1101_FREQ2 0x0D // Frequency Control Word, High Byte
#define CC1101_FREQ1 0x0E // Frequency Control Word, Middle Byte
#define CC1101_FREQ0 0x0F // Frequency Control Word, Low Byte
#define CC1101_MDMCFG4 0x10 // Modem Configuration
#define CC1101_MDMCFG3 0x11 // Modem Configuration
#define CC1101_MDMCFG2 0x12 // Modem Configuration
#define CC1101_MDMCFG1 0x13 // Modem Configuration
#define CC1101_MDMCFG0 0x14 // Modem Configuration
#define CC1101_DEVIATN 0x15 // Modem Deviation Setting
#define CC1101_MCSM2 0x16 // Main Radio Control State Machine Configuration
#define CC1101_MCSM1 0x17 // Main Radio Control State Machine Configuration
#define CC1101_MCSM0 0x18 // Main Radio Control State Machine Configuration
#define CC1101_FOCCFG 0x19 // Frequency Offset Compensation Configuration
#define CC1101_BSCFG 0x1A // Bit Synchronization Configuration
#define CC1101_AGCCTRL2 0x1B // AGC Control
#define CC1101_AGCCTRL1 0x1C // AGC Control
#define CC1101_AGCCTRL0 0x1D // AGC Control
#define CC1101_WOREVT1 0x1E // High Byte Event0 Timeout
#define CC1101_WOREVT0 0x1F // Low Byte Event0 Timeout
#define CC1101_WORCTRL 0x20 // Wake On Radio Control
#define CC1101_FREND1 0x21 // Front End RX Configuration
#define CC1101_FREND0 0x22 // Front End TX Configuration
#define CC1101_FSCAL3 0x23 // Frequency Synthesizer Calibration
#define CC1101_FSCAL2 0x24 // Frequency Synthesizer Calibration
#define CC1101_FSCAL1 0x25 // Frequency Synthesizer Calibration
#define CC1101_FSCAL0 0x26 // Frequency Synthesizer Calibration
#define CC1101_RCCTRL1 0x27 // RC Oscillator Configuration
#define CC1101_RCCTRL0 0x28 // RC Oscillator Configuration
#define CC1101_FSTEST 0x29 // Frequency Synthesizer Calibration Control
#define CC1101_PTEST 0x2A // Production Test
#define CC1101_AGCTEST 0x2B // AGC Test
#define CC1101_TEST2 0x2C // Various Test Settings
#define CC1101_TEST1 0x2D // Various Test Settings
#define CC1101_TEST0 0x2E // Various Test Settings
/**
* Status registers
*/
#define CC1101_PARTNUM 0x30 // Chip ID
#define CC1101_VERSION 0x31 // Chip ID
#define CC1101_FREQEST 0x32 // Frequency Offset Estimate from Demodulator
#define CC1101_LQI 0x33 // Demodulator Estimate for Link Quality
#define CC1101_RSSI 0x34 // Received Signal Strength Indication
#define CC1101_MARCSTATE 0x35 // Main Radio Control State Machine State
#define CC1101_WORTIME1 0x36 // High Byte of WOR Time
#define CC1101_WORTIME0 0x37 // Low Byte of WOR Time
#define CC1101_PKTSTATUS 0x38 // Current GDOx Status and Packet Status
#define CC1101_VCO_VC_DAC 0x39 // Current Setting from PLL Calibration Module
#define CC1101_TXBYTES 0x3A // Underflow and Number of Bytes
#define CC1101_RXBYTES 0x3B // Overflow and Number of Bytes
#define CC1101_RCCTRL1_STATUS 0x3C // Last RC Oscillator Calibration Result
#define CC1101_RCCTRL0_STATUS 0x3D // Last RC Oscillator Calibration Result
/**
* CC1101 configuration registers - Default values extracted from SmartRF Studio
*
* Configuration:
*
* Deviation = 20.629883
* Base frequency = 867.999939
* Carrier frequency = 867.999939
* Channel number = 0
* Carrier frequency = 867.999939
* Modulated = true
* Modulation format = GFSK
* Manchester enable = false
* Data whitening = off
* Sync word qualifier mode = 30/32 sync word bits detected
* Preamble count = 4
* Channel spacing = 199.951172
* Carrier frequency = 867.999939
* Data rate = 38.3835 Kbps
* RX filter BW = 101.562500
* Data format = Normal mode
* Length config = Variable packet length mode. Packet length configured by the first byte after sync word
* CRC enable = true
* Packet length = 255
* Device address = 1
* Address config = Enable address check
* Append status = Append two status bytes to the payload of the packet. The status bytes contain RSSI and
* LQI values, as well as CRC OK
* CRC autoflush = false
* PA ramping = false
* TX power = 12
* GDO0 mode = Asserts when sync word has been sent / received, and de-asserts at the end of the packet.
* In RX, the pin will also de-assert when a packet is discarded due to address or maximum length filtering
* or when the radio enters RXFIFO_OVERFLOW state. In TX the pin will de-assert if the TX FIFO underflows
* Settings optimized for low current consumption
*/
//#define CC1101_DEFVAL_IOCFG2 0x29 // GDO2 Output Pin Configuration
#define CC1101_DEFVAL_IOCFG2 0x0D // GDO2 Output Pin Configuration
#define CC1101_DEFVAL_IOCFG1 0x2E // GDO1 Output Pin Configuration
#define CC1101_DEFVAL_IOCFG0 0x2D // GDO0 Output Pin Configuration
#define CC1101_DEFVAL_FIFOTHR 0x07 // RX FIFO and TX FIFO Thresholds
#define CC1101_DEFVAL_SYNC1 0xD3 // Synchronization word, high byte
#define CC1101_DEFVAL_SYNC0 0x91 // Synchronization word, low byte
#define CC1101_DEFVAL_PKTLEN 0x3D // Packet Length
#define CC1101_DEFVAL_PKTCTRL1 0x04 // Packet Automation Control
#define CC1101_DEFVAL_PKTCTRL0 0x32 // Packet Automation Control
#define CC1101_DEFVAL_ADDR 0xFF // Device Address
#define CC1101_DEFVAL_CHANNR 0x00 // Channel Number
#define CC1101_DEFVAL_FSCTRL1 0x06 // Frequency Synthesizer Control
#define CC1101_DEFVAL_FSCTRL0 0x00 // Frequency Synthesizer Control
// Carrier frequency = 868 MHz
#define CC1101_DEFVAL_FREQ2_868 0x21 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_868 0x62 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_868 0x76 // Frequency Control Word, Low Byte
// Carrier frequency = 902 MHz
#define CC1101_DEFVAL_FREQ2_915 0x22 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_915 0xB1 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_915 0x3B // Frequency Control Word, Low Byte
// Carrier frequency = 918 MHz
#define CC1101_DEFVAL_FREQ2_918 0x23 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_918 0x4E // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_918 0xC4 // Frequency Control Word, Low Byte
// Carrier frequency = 433 MHz
#define CC1101_DEFVAL_FREQ2_433 0x10 // Frequency Control Word, High Byte
#define CC1101_DEFVAL_FREQ1_433 0xB0 // Frequency Control Word, Middle Byte
#define CC1101_DEFVAL_FREQ0_433 0xB0 // Frequency Control Word, Low Byte
#define CC1101_DEFVAL_MDMCFG4 0xA9 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG3 0xE4 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG2 0x30 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG1 0x22 // Modem Configuration
#define CC1101_DEFVAL_MDMCFG0 0xF8 // Modem Configuration
#define CC1101_DEFVAL_DEVIATN 0x00 // Modem Deviation Setting
#define CC1101_DEFVAL_MCSM2 0x07 // Main Radio Control State Machine Configuration
//#define CC1101_DEFVAL_MCSM1 0x30 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_MCSM1 0x30 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_MCSM0 0x18 // Main Radio Control State Machine Configuration
#define CC1101_DEFVAL_FOCCFG 0x14 // Frequency Offset Compensation Configuration
#define CC1101_DEFVAL_BSCFG 0x6C // Bit Synchronization Configuration
#define CC1101_DEFVAL_AGCCTRL2 0x04 // AGC Control
#define CC1101_DEFVAL_AGCCTRL1 0x00 // AGC Control
#define CC1101_DEFVAL_AGCCTRL0 0x92 // AGC Control
#define CC1101_DEFVAL_WOREVT1 0x87 // High Byte Event0 Timeout
#define CC1101_DEFVAL_WOREVT0 0x6B // Low Byte Event0 Timeout
#define CC1101_DEFVAL_WORCTRL 0xF8 // Wake On Radio Control
#define CC1101_DEFVAL_FREND1 0xB6 // Front End RX Configuration
#define CC1101_DEFVAL_FREND0 0x11 // Front End TX Configuration
#define CC1101_DEFVAL_FSCAL3 0xE9 // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL2 0x2A // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL1 0x00 // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_FSCAL0 0x1F // Frequency Synthesizer Calibration
#define CC1101_DEFVAL_RCCTRL1 0x41 // RC Oscillator Configuration
#define CC1101_DEFVAL_RCCTRL0 0x00 // RC Oscillator Configuration
#define CC1101_DEFVAL_FSTEST 0x59 // Frequency Synthesizer Calibration Control
#define CC1101_DEFVAL_PTEST 0x7F // Production Test
#define CC1101_DEFVAL_AGCTEST 0x3F // AGC Test
#define CC1101_DEFVAL_TEST2 0x81 // Various Test Settings
#define CC1101_DEFVAL_TEST1 0x35 // Various Test Settings
#define CC1101_DEFVAL_TEST0 0x09 // Various Test Settings
/**
* Alias for some default values
*/
#define CCDEF_CHANNR CC1101_DEFVAL_CHANNR
#define CCDEF_SYNC0 CC1101_DEFVAL_SYNC0
#define CCDEF_SYNC1 CC1101_DEFVAL_SYNC1
#define CCDEF_ADDR CC1101_DEFVAL_ADDR
/**
* Macros
*/
// Read CC1101 Config register
#define readConfigReg(regAddr) readReg(regAddr, CC1101_CONFIG_REGISTER)
// Read CC1101 Status register
#define readStatusReg(regAddr) readReg(regAddr, CC1101_STATUS_REGISTER)
// Enter Rx state
//#define setRxState() cmdStrobe(CC1101_SRX)
// Enter Tx state
//#define setTxState() cmdStrobe(CC1101_STX)
// Enter IDLE state
#define setIdleState() cmdStrobe(CC1101_SIDLE)
// Flush Rx FIFO
#define flushRxFifo() cmdStrobe(CC1101_SFRX)
// Flush Tx FIFO
#define flushTxFifo() cmdStrobe(CC1101_SFTX)
// Disable address check
#define disableAddressCheck() writeReg(CC1101_PKTCTRL1, 0x04)
// Enable address check
#define enableAddressCheck() writeReg(CC1101_PKTCTRL1, 0x06)
// Disable CCA
#define disableCCA() writeReg(CC1101_MCSM1, 0)
// Enable CCA
#define enableCCA() writeReg(CC1101_MCSM1, CC1101_DEFVAL_MCSM1)
// Set PATABLE single byte
#define setTxPowerAmp(setting) paTableByte = setting
// PATABLE values
#define PA_LowPower 0x60
#define PA_LongDistance 0xC0
/**
* Class: CC1101
*
* Description:
* CC1101 interface
*/
class CC1101
{
private:
/**
* Atmega's SPI interface
*/
SPIClass spi;
/**
* writeBurstReg
*
* Write multiple registers into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'buffer' Data to be writen
* 'len' Data length
*/
void writeBurstReg(uint8_t regAddr, uint8_t* buffer, uint8_t len);
/**
* readBurstReg
*
* Read burst data from CC1101 via SPI
*
* 'buffer' Buffer where to copy the result to
* 'regAddr' Register address
* 'len' Data length
*/
void readBurstReg(uint8_t * buffer, uint8_t regAddr, uint8_t len);
/**
* setRegsFromEeprom
*
* Set registers from EEPROM
*/
void setRegsFromEeprom(void);
public:
/*
* RF state
*/
uint8_t rfState;
/**
* Tx Power byte (single PATABLE config)
*/
uint8_t paTableByte;
/**
* Carrier frequency
*/
uint8_t carrierFreq;
/**
* Frequency channel
*/
uint8_t channel;
/**
* Synchronization word
*/
uint8_t syncWord[2];
/**
* Device address
*/
uint8_t devAddress;
/**
* CC1101
*
* Class constructor
*/
CC1101(void);
/**
* cmdStrobe
*
* Send command strobe to the CC1101 IC via SPI
*
* 'cmd' Command strobe
*/
void cmdStrobe(uint8_t cmd);
/**
* wakeUp
*
* Wake up CC1101 from Power Down state
*/
void wakeUp(void);
/**
* readReg
*
* Read CC1101 register via SPI
*
* 'regAddr' Register address
* 'regType' Type of register: CC1101_CONFIG_REGISTER or CC1101_STATUS_REGISTER
*
* Return:
* Data byte returned by the CC1101 IC
*/
uint8_t readReg(uint8_t regAddr, uint8_t regType);
/**
* writeReg
*
* Write single register into the CC1101 IC via SPI
*
* 'regAddr' Register address
* 'value' Value to be writen
*/
void writeReg(uint8_t regAddr, uint8_t value);
/**
* setCCregs
*
* Configure CC1101 registers
*/
void setCCregs(void);
/**
* reset
*
* Reset CC1101
*/
void reset(void);
/**
* init
*
* Initialize CC1101 radio
*
* @param freq Carrier frequency
*/
void init(uint8_t freq=CFREQ_868);
/**
* setSyncWord
*
* Set synchronization word
*
* 'syncH' Synchronization word - High byte
* 'syncL' Synchronization word - Low byte
*/
void setSyncWord(uint8_t syncH, uint8_t syncL);
/**
* setSyncWord (overriding method)
*
* Set synchronization word
*
* 'syncH' Synchronization word - pointer to 2-byte array
*/
void setSyncWord(uint8_t *sync);
/**
* setDevAddress
*
* Set device address
*
* 'addr' Device address
*/
void setDevAddress(uint8_t addr);
/**
* setCarrierFreq
*
* Set carrier frequency
*
* 'freq' New carrier frequency
*/
void setCarrierFreq(uint8_t freq);
/**
* setChannel
*
* Set frequency channel
*
* 'chnl' Frequency channel
*/
void setChannel(uint8_t chnl);
/**
* setPowerDownState
*
* Put CC1101 into power-down state
*/
void setPowerDownState();
/**
* sendData
*
* Send data packet via RF
*
* 'packet' Packet to be transmitted. First byte is the destination address
*
* Return:
* True if the transmission succeeds
* False otherwise
*/
bool sendData(CCPACKET packet);
/**
* receiveData
*
* Read data packet from RX FIFO
*
* Return:
* Amount of bytes received
*/
uint8_t receiveData(CCPACKET *packet);
/**
* setRxState
*
* Enter Rx state
*/
void setRxState(void);
/**
* setTxState
*
* Enter Tx state
*/
void setTxState(void);
};
#endif

70
lib/cc1101/ccpacket.h Normal file
View File

@ -0,0 +1,70 @@
/**
* Copyright (c) 2011 panStamp <contact@panstamp.com>
*
* This file is part of the panStamp project.
*
* panStamp 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
* any later version.
*
* panStamp is distributed in the hope that 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 panStamp; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301
* USA
*
* Author: Daniel Berenguer
* Creation date: 06/03/2013
*/
#ifndef _CCPACKET_H
#define _CCPACKET_H
/**
* Buffer and data lengths
*/
#define CCPACKET_BUFFER_LEN 64
#define CCPACKET_DATA_LEN CCPACKET_BUFFER_LEN - 3
/**
* Class: CCPACKET
*
* Description:
* CC1101 data packet class
*/
struct CCPACKET
{
public:
/**
* Data length
*/
unsigned char length;
/**
* Data buffer
*/
unsigned char data[CCPACKET_DATA_LEN];
/**
* CRC OK flag
*/
bool crc_ok;
/**
* Received Strength Signal Indication
*/
unsigned char rssi;
/**
* Link Quality Index
*/
unsigned char lqi;
};
#endif

View File

@ -418,6 +418,7 @@
#define USE_DEVICE_GROUPS // Add support for device groups (+5k6 code)
#define USE_PWM_DIMMER // Add support for MJ-SD01/acenx/NTONPOWER PWM dimmers (+4k5 code)
#define USE_PWM_DIMMER_REMOTE // Add support for remote switches to PWM Dimmer, also adds device groups support (+0k7 code, also includes device groups)
//#define USE_KEELOQ // Add support for controling Jarolift rollers by Keeloq algorithm
// -- Optional light modules ----------------------
#define USE_WS2812 // WS2812 Led string using library NeoPixelBus (+5k code, +1k mem, 232 iram) - Disable by //

View File

@ -469,9 +469,12 @@ struct SYSCFG {
uint8_t bri_min; // F05
uint8_t bri_preset_low; // F06
uint8_t bri_preset_high; // F07
uint8_t free_f08[180]; // F08
uint8_t free_f05[196]; // F08
uint32_t keeloq_master_msb; // FBC
uint32_t keeloq_master_lsb; // FC0
uint32_t keeloq_serial; // FC4
uint32_t keeloq_count; // FC8
uint32_t device_group_share_in; // FCC - Bitmask of device group items imported
uint32_t device_group_share_out; // FD0 - Bitmask of device group items exported
uint32_t bootcount_reset_time; // FD4

273
tasmota/xdrv_36_keeloq.ino Normal file
View File

@ -0,0 +1,273 @@
/*
xdrv_36
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 3 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, see <http://www.gnu.org/licenses/>.
*/
#ifdef USE_KEELOQ
#define XDRV_36 36
#include "cc1101.h"
#include <KeeloqLib.h>
#define SYNC_WORD 199
#define Lowpulse 400
#define Highpulse 800
#define TX_PORT 4 // Outputport for transmission
#define RX_PORT 5 // Inputport for reception
const char kJaroliftCommands[] PROGMEM = "Keeloq|" // prefix
"SendRaw|SendButton|Set";
void (* const jaroliftCommand[])(void) PROGMEM = {
&CmndSendRaw, &CmdSendButton, &CmdSet};
CC1101 cc1101;
struct JAROLIFT_DEVICE {
int device_key_msb = 0x0; // stores cryptkey MSB
int device_key_lsb = 0x0; // stores cryptkey LSB
uint64_t button = 0x0; // 1000=0x8 up, 0100=0x4 stop, 0010=0x2 down, 0001=0x1 learning
int disc = 0x0100; // 0x0100 for single channel remote
uint32_t enc = 0x0; // stores the 32Bit encrypted code
uint64_t pack = 0; // Contains data to send.
int count = 0;
uint32_t serial = 0x0;
} jaroliftDevice;
void CmdSet(void)
{
if (XdrvMailbox.data_len > 0) {
if (XdrvMailbox.payload > 0) {
char *p;
uint32_t i = 0;
uint32_t param[4] = { 0 };
for (char *str = strtok_r(XdrvMailbox.data, ", ", &p); str && i < 4; str = strtok_r(nullptr, ", ", &p)) {
param[i] = strtoul(str, nullptr, 0);
i++;
}
for (uint32_t i = 0; i < 3; i++) {
if (param[i] < 1) { param[i] = 1; } // msb, lsb, serial, counter
}
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("params: %08x %08x %08x %08x"), param[0], param[1], param[2], param[3]);
Settings.keeloq_master_msb = param[0];
Settings.keeloq_master_lsb = param[1];
Settings.keeloq_serial = param[2];
Settings.keeloq_count = param[3];
jaroliftDevice.serial = param[2];
jaroliftDevice.count = param[3];
GenerateDeviceCryptKey();
ResponseCmndDone();
} else {
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("no payload"));
}
} else {
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("no param"));
}
}
void GenerateDeviceCryptKey()
{
Keeloq k(Settings.keeloq_master_msb, Settings.keeloq_master_lsb);
jaroliftDevice.device_key_msb = k.decrypt(jaroliftDevice.serial | 0x60000000L);
jaroliftDevice.device_key_lsb = k.decrypt(jaroliftDevice.serial | 0x20000000L);
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("generated device keys: %08x %08x"), jaroliftDevice.device_key_msb, jaroliftDevice.device_key_lsb);
}
void CmdSendButton(void)
{
noInterrupts();
entertx();
if (XdrvMailbox.data_len > 0)
{
if (XdrvMailbox.payload > 0)
{
jaroliftDevice.button = strtoul(XdrvMailbox.data, nullptr, 0);
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("msb: %08x"), jaroliftDevice.device_key_msb);
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("lsb: %08x"), jaroliftDevice.device_key_lsb);
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("serial: %08x"), jaroliftDevice.serial);
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("disc: %08x"), jaroliftDevice.disc);
AddLog_P2(LOG_LEVEL_DEBUG, PSTR("KLQ: count: %08x"), jaroliftDevice.count);
CreateKeeloqPacket();
jaroliftDevice.count++;
Settings.keeloq_count = jaroliftDevice.count;
for(int repeat = 0; repeat <= 1; repeat++)
{
uint64_t bitsToSend = jaroliftDevice.pack;
digitalWrite(TX_PORT, LOW);
delayMicroseconds(1150);
SendSyncPreamble(13);
delayMicroseconds(3500);
for(int i=72; i>0; i--)
{
SendBit(bitsToSend & 0x0000000000000001);
bitsToSend >>= 1;
}
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("finished sending bits at %d"), micros());
delay(16); // delay in loop context is save for wdt
}
}
}
interrupts();
enterrx();
ResponseCmndDone();
}
void SendBit(byte bitToSend)
{
if (bitToSend==1)
{
digitalWrite(TX_PORT, LOW); // Simple encoding of bit state 1
delayMicroseconds(Lowpulse);
digitalWrite(TX_PORT, HIGH);
delayMicroseconds(Highpulse);
}
else
{
digitalWrite(TX_PORT, LOW); // Simple encoding of bit state 0
delayMicroseconds(Highpulse);
digitalWrite(TX_PORT, HIGH);
delayMicroseconds(Lowpulse);
}
}
void CmndSendRaw(void)
{
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("cmd send called at %d"), micros());
noInterrupts();
entertx();
for(int repeat = 0; repeat <= 1; repeat++)
{
if (XdrvMailbox.data_len > 0)
{
digitalWrite(TX_PORT, LOW);
delayMicroseconds(1150);
SendSyncPreamble(13);
delayMicroseconds(3500);
for(int i=XdrvMailbox.data_len-1; i>=0; i--)
{
SendBit(XdrvMailbox.data[i] == '1');
}
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("finished sending bits at %d"), micros());
delay(16); // delay in loop context is save for wdt
}
interrupts();
}
enterrx();
ResponseCmndDone();
}
void enterrx() {
unsigned char marcState = 0;
cc1101.setRxState();
delay(2);
unsigned long rx_time = micros();
while (((marcState = cc1101.readStatusReg(CC1101_MARCSTATE)) & 0x1F) != 0x0D )
{
if (micros() - rx_time > 50000) break; // Quit when marcState does not change...
}
}
void entertx() {
unsigned char marcState = 0;
cc1101.setTxState();
delay(2);
unsigned long rx_time = micros();
while (((marcState = cc1101.readStatusReg(CC1101_MARCSTATE)) & 0x1F) != 0x13 && 0x14 && 0x15)
{
if (micros() - rx_time > 50000) break; // Quit when marcState does not change...
}
}
void SendSyncPreamble(int l)
{
for (int i = 0; i < l; ++i)
{
digitalWrite(TX_PORT, LOW);
delayMicroseconds(400);
digitalWrite(TX_PORT, HIGH);
delayMicroseconds(380);
}
}
void CreateKeeloqPacket()
{
Keeloq k(jaroliftDevice.device_key_msb, jaroliftDevice.device_key_lsb);
unsigned int result = (jaroliftDevice.disc << 16) | jaroliftDevice.count;
jaroliftDevice.pack = (uint64_t)0;
jaroliftDevice.pack |= jaroliftDevice.serial & 0xfffffffL;
jaroliftDevice.pack |= (jaroliftDevice.button & 0xfL) << 28;
jaroliftDevice.pack <<= 32;
jaroliftDevice.enc = k.encrypt(result);
jaroliftDevice.pack |= jaroliftDevice.enc;
AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("pack high: %08x"), jaroliftDevice.pack>>32);
AddLog_P2(LOG_LEVEL_DEBUG_MORE, PSTR("pack low: %08x"), jaroliftDevice.pack);
}
void InitKeeloq()
{
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("cc1101.init()"));
delay(100);
cc1101.init();
AddLog_P(LOG_LEVEL_DEBUG_MORE, PSTR("CC1101 done."));
cc1101.setSyncWord(SYNC_WORD, false);
cc1101.setCarrierFreq(CFREQ_433);
cc1101.disableAddressCheck();
pinMode(TX_PORT, OUTPUT);
pinMode(RX_PORT, INPUT_PULLUP);
jaroliftDevice.serial = Settings.keeloq_serial;
jaroliftDevice.count = Settings.keeloq_count;
GenerateDeviceCryptKey();
}
/*********************************************************************************************\
* Interface
\*********************************************************************************************/
bool Xdrv36(uint8_t function)
{
bool result = false;
switch (function) {
case FUNC_INIT:
InitKeeloq();
DEBUG_DRIVER_LOG(LOG_LEVEL_DEBUG_MORE, PSTR("init done."));
break;
case FUNC_COMMAND:
AddLog_P(LOG_LEVEL_DEBUG_MORE, PSTR("calling command"));
result = DecodeCommand(kJaroliftCommands, jaroliftCommand);
break;
}
return result;
}
#endif // USE_KEELOQ