Buongiorno,chiedo scusa a tutti,riformulo il problema in italiano con la speranza che qualcuno possa aiutarmi.Siccome stò realizzando una piccol,a ricevente per un micro aereo ho necessità per questioni di riduzione di peso di portare il codice originario da un atmega328 ad un piccolo attiny1616,il tutto ovviamnente tramite arduino.Gran parte del codice son riuscito a modificarla,resta solo una parte che non sò come trasformarla per farla interpretare dall'attiny.La parte che non riesco a modificare(non sò come) è la seguente:
#define SDI_1 (PIN4 & 0x02) == 0x02
#define SDI_0 (PIN4 & 0x02) == 0x00
#define GIO_1 (PIN5 & 0x01) == 0x01
#define GIO_0 (PIN5 & 0x01) == 0x00
//*
//*V2
//* FlySky car receiver modify by Ivan con Autobind
//Faisafe
//#define DEBUG
//#define SERIAL_BAUD_RATE 9600
#include <EEPROM.h>
#include <Servo.h>
static const uint8_t A7105_regs[] = {
0xff, 0x42, 0x00, 0x14, 0x00, 0xff, 0xff , 0x00, 0x00, 0x00, 0x00, 0x01, 0x21, 0x05, 0x00, 0x50,
0x9e, 0x4b, 0x00, 0x02, 0x16, 0x2b, 0x12, 0x00, 0x62, 0x80, 0x80, 0x00, 0x0a, 0x32, 0xc3, 0x0f,
0x13, 0xc3, 0x00, 0xff, 0x00, 0x00, 0x3b, 0x00, 0x17, 0x47, 0x80, 0x03, 0x01, 0x45, 0x18, 0x00,
0x01, 0x0f, 0xff,
};
static const uint8_t tx_channels[16][16] = {
{0x0a, 0x5a, 0x14, 0x64, 0x1e, 0x6e, 0x28, 0x78, 0x32, 0x82, 0x3c, 0x8c, 0x46, 0x96, 0x50, 0xa0},
{0xa0, 0x50, 0x96, 0x46, 0x8c, 0x3c, 0x82, 0x32, 0x78, 0x28, 0x6e, 0x1e, 0x64, 0x14, 0x5a, 0x0a},
{0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x46, 0x96, 0x1e, 0x6e, 0x3c, 0x8c, 0x28, 0x78, 0x32, 0x82},
{0x82, 0x32, 0x78, 0x28, 0x8c, 0x3c, 0x6e, 0x1e, 0x96, 0x46, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a},
{0x28, 0x78, 0x0a, 0x5a, 0x50, 0xa0, 0x14, 0x64, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96},
{0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x64, 0x14, 0xa0, 0x50, 0x5a, 0x0a, 0x78, 0x28},
{0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x3c, 0x8c, 0x32, 0x82, 0x46, 0x96, 0x14, 0x64},
{0x64, 0x14, 0x96, 0x46, 0x82, 0x32, 0x8c, 0x3c, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50},
{0x50, 0xa0, 0x46, 0x96, 0x3c, 0x8c, 0x28, 0x78, 0x0a, 0x5a, 0x32, 0x82, 0x1e, 0x6e, 0x14, 0x64},
{0x64, 0x14, 0x6e, 0x1e, 0x82, 0x32, 0x5a, 0x0a, 0x78, 0x28, 0x8c, 0x3c, 0x96, 0x46, 0xa0, 0x50},
{0x46, 0x96, 0x3c, 0x8c, 0x50, 0xa0, 0x28, 0x78, 0x0a, 0x5a, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x5a, 0x0a, 0x78, 0x28, 0xa0, 0x50, 0x8c, 0x3c, 0x96, 0x46},
{0x46, 0x96, 0x0a, 0x5a, 0x3c, 0x8c, 0x14, 0x64, 0x50, 0xa0, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82},
{0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0xa0, 0x50, 0x64, 0x14, 0x8c, 0x3c, 0x5a, 0x0a, 0x96, 0x46},
{0x46, 0x96, 0x0a, 0x5a, 0x50, 0xa0, 0x3c, 0x8c, 0x28, 0x78, 0x1e, 0x6e, 0x32, 0x82, 0x14, 0x64},
{0x64, 0x14, 0x82, 0x32, 0x6e, 0x1e, 0x78, 0x28, 0x8c, 0x3c, 0xa0, 0x50, 0x5a, 0x0a, 0x96, 0x46},
};
#define FAILSAFE
//#define GIO_pin 1 ATMEGA328
//#define SDI_pin 5 ATMEGA328
//#define SCLK_pin 3 ATMEGA328
//#define CS_pin 2 ATMEGA328
//Fari
//#define LED 3
Servo servo1;
Servo servo2;
Servo servo3;
Servo servo4;
//#define CS_on PORTC |= 0x08 // ATMEGA328
//#define CS_off PORTC &= 0xF7 // ATMEGA328
//#define SCK_on PORTC |= 0x04 // ATMEGA328
//#define SCK_off PORTC &= 0xFB // ATMEGA328
//#define SDI_on PORTC |= 0x02 // ATMEGA328
//#define SDI_off PORTC &= 0xFD // ATMGA328
//#define GIO_on PORTC |=0x01 // ATMEGA328
//#define SDI_1 (PINC & 0x02) == 0x02 // ATMEGA328
//#define SDI_0 (PINC & 0x02) == 0x00 // ATMEGA328
//#define GIO_1 (PINC & 0x01) == 0x01 // ATMEGA328
//#define GIO_0 (PINC & 0x01) == 0x00 // ATMEGA328
#define CS_on PORTA.OUT |= PIN6_bm //PA6 ATTINY1616
#define CS_off PORTA.OUT &= ~PIN6_bm //PA6 ATTINY1616
#define SCK_on PORTA.OUT |= PIN7_bm //PA7 ATTINY1616
#define SCK_off PORTA.OUT &= ~PIN7_bm //PA7 ATTINY1616
#define SDI_on PORTB.OUT |= PIN4_bm //PB4 ATTINY1616
#define SDI_off PORTB.OUT &= ~PIN4_bm //PB4 ATTINY1616
#define GIO_on PORTA.IN & PIN5_bm //PA5 ATTINY1616
#define SDI_1 (PIN4 & 0x02) == 0x02 //Atmega328...ATTINY1616???
#define SDI_0 (PIN4 & 0x02) == 0x00 //Atmega328...ATTINY1616???
#define GIO_1 (PIN5 & 0x01) == 0x01 //Atmega328...ATTINY1616???
#define GIO_0 (PIN5 & 0x01) == 0x00 //Atmega328...ATTINY1616???
//#define RED_LED_pin 0
#define Red_LED_ON PORTA.OUTSET = _BV(4);
#define Red_LED_OFF PORTA.OUTCLR = _BV(4);
#define NOP() __asm__ __volatile__("nop")
static uint32_t id;
static uint8_t txid[4]; //4
static uint16_t word_temp;
static uint8_t chanrow;
static uint8_t chancol;
static uint8_t chanoffset;
static uint8_t channel;
static uint8_t aid[4];
static word counter1 = 512;
static uint8_t packet[21];
static uint16_t Servo_data[10] = {1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500};
static uint16_t total_servo_time = 0;
static byte cur_chan_numb = 0;
static uint16_t failsafeCnt = 0; //Failsafe
volatile byte scale;
void setup() {
// Servo pins
servo1.attach(6); //Elevatore
servo2.attach(7); //Alettoni
servo3.attach(8);//Sterzo/Timone
servo4.attach(9);//gas
// pinMode(RED_LED_pin, OUTPUT);//Bind Led //ATMEGA328
// pinMode(SDI_pin, OUTPUT); ATMEGA328
// pinMode(SCLK_pin, OUTPUT); ATMEGA328
// pinMode(CS_pin, OUTPUT); ATMEGA328
// pinMode(GIO_pin, INPUT); ATMEGA328
PORTA.DIRSET = PIN6_bm; // use PA6 as an output //CS ATTINY1616
PORTA.DIRSET = PIN7_bm; // use PA7 as an output //SCK ATTINY1616
PORTB.DIRSET = PIN4_bm; // use PB4 as an output //SDI ATTINY1616
//PORTA.DIRSET = PIN5_bm; // use PA5 as an output // GIO ATTINY1616
PORTA.DIRCLR = PIN5_bm; //use PA5 as an input //GIO ATTINY1616
PORTA.DIRSET = PIN4_bm; // use PA4 as LedPin ATTINY1616
// pinMode(5, OUTPUT);
// pinMode(6, OUTPUT);
// pinMode(7, OUTPUT);
// pinMode(10, OUTPUT);
//pinMode(3, OUTPUT);//Fari
CS_on;
SDI_on;
SCK_off;
# if defined(DEBUG)
Serial.begin(SERIAL_BAUD_RATE);//for debug
#endif
uint8_t i;
uint8_t if_calibration1;
uint8_t vco_calibration0;
uint8_t vco_calibration1;
delay(10);
_spi_write_adress(0x00, 0x00);
A7105_WriteID(0x5475c52A);
A7105_ReadID();
for (i = 0; i < 0x33; i++) {
if (A7105_regs[i] != 0xff)
_spi_write_adress(i, A7105_regs[i]);
}
_spi_strobe(0xA0);
_spi_write_adress(0x02, 0x01);
while (_spi_read_adress(0x02)) {
if_calibration1 = _spi_read_adress(0x22);
if (if_calibration1 & 0x10) {
}
}
_spi_write_adress(0x24, 0x13);
_spi_write_adress(0x26, 0x3b);
_spi_write_adress(0x0F, 0x00);
_spi_write_adress(0x02, 0x02);
while (_spi_read_adress(0x02)) {
vco_calibration0 = _spi_read_adress(0x25);
if (vco_calibration0 & 0x08) {
}
}
_spi_write_adress(0x0F, 0xA0);
_spi_write_adress(0x02, 0x02);
while (_spi_read_adress(0x02)) {
vco_calibration1 = _spi_read_adress(0x25);
if (vco_calibration1 & 0x08) {
}
}
_spi_write_adress(0x25, 0x08);
_spi_strobe(0xA0);
//
bind_Flysky();
id = (txid[0] | ((uint32_t)txid[1] << 8) | ((uint32_t)txid[2] << 16) | ((uint32_t)txid[3] << 24));
chanrow = id % 16;
chanoffset = (id & 0xff) / 16;
chancol = 0;
if (chanoffset > 9) chanoffset = 9;
#if F_CPU == 16000000// thanks to goebish for this nice idea.
scale = 2;
#elif F_CPU == 8000000
scale = 1;
#else
//#error // 8 or 16MHz only !
#endif
}
void loop() {
channel = tx_channels[chanrow][chancol] - 1 - chanoffset;
_spi_strobe(0xA0);
_spi_strobe(0xF0);
_spi_write_adress(0x0F, channel);
_spi_strobe(0xC0);
chancol = (chancol + 1) % 16;
unsigned long pause;
uint8_t x;
pause = micros();
while (1) {
//
#if defined(FAILSAFE)//NEW
uint8_t n;
if (failsafeCnt > 500) { //Faisafe = 0.5 secondi!
failsafeCnt = 0;
Servo_data[2] = 1500; //ER9x, thr min, rest center
for (n = 0; n < 2; n++) {
Servo_data[n] = 1500;
}
for (n = 3; n < 8; n++) {
Servo_data[n] = 1500;
}
#if defined(DEBUG)
Serial.println("failsafe!");
#endif
send_command();
}
#endif
if ((micros() - pause) > 2000) {
Red_LED_OFF;
chancol = (chancol + 1) % 16;
channel = tx_channels[chanrow][chancol] - 1 - chanoffset;
failsafeCnt++;//New
break;
}
if (GIO_1) {
continue;
}
x = _spi_read_adress(0x00);
if (!(bitRead(x, 5) == 0) && !(bitRead(x, 6) == 0)) {
continue;
}
Read_Packet();
if (!(packet[1] == txid[0]) && !(packet[2] == txid[1]) && !(packet[3] == txid[2]) && !(packet[4] == txid[3])) {
continue;
}
Red_LED_ON;
failsafeCnt = 0; //NEW
uint8_t i;
//cli();
for (i = 0; i < 8; i++) {
word_temp = (packet[5 + (2 * i)] + 256 * packet[6 + (2 * i)]);
if ((word_temp > 900) && (word_temp < 2200))
Servo_data[i] = word_temp;
}
send_command();
}
}
void send_command(){
//Servo Mappatura
servo1.write(map(Servo_data[1], 1000, 2000, 0, 180)); //Elevatore 30° 150°
servo2.write(map(Servo_data[3], 1000, 2000, 0, 180)); //Alettoni
servo3.write(map(Servo_data[0], 1000, 2000, 0, 180)); //Sterzo/Timo
servo4.write(map(Servo_data[2], 1000, 2000, 0, 180)); //gas
}
//BIND_TX
void bind_Flysky() {
uint8_t flag = 0;
while (1) {
_spi_strobe(0xA0);
_spi_strobe(0xF0);
_spi_write_adress(0x0F, 0x00); //binding listen on channel 0
_spi_strobe(0xC0);
while (counter1) { //counter for 5 sec.
delay(10);//wait 10ms
if (bitRead(counter1, 2) == 1) {
Red_LED_ON;
}
if (bitRead(counter1, 2) == 0) {
Red_LED_OFF;
}
if (GIO_0) {
uint8_t x;
x = _spi_read_adress(0x00);
if ((bitRead(x, 5) == 0) && (bitRead(x, 6) == 0)) { //test CRC&CRF bits
Read_Packet();
uint8_t i;
uint8_t adr = 10;
for (i = 0; i < 4; i++) {
EEPROM.write(adr, packet[i + 1]);
adr = adr + 1;
txid[i] = packet[i + 1];
}
break;
}
else {
flag = 1;
break;
}
}
counter1--;
if (counter1) {
continue;
}
else {
uint8_t i;
uint8_t adr = 10;
for (i = 0; i < 4; i++) {
txid[i] = EEPROM.read(adr);
adr = adr + 1;
}
break;
}
}
if (flag == 1)
continue;
break;
}
}
//-------------------------------
//-------------------------------
//A7105 SPI routines
//-------------------------------
//-------------------------------
void A7105_WriteID(uint32_t ida) {
CS_off;
_spi_write(0x06);
_spi_write((ida >> 24) & 0xff);
_spi_write((ida >> 16) & 0xff);
_spi_write((ida >> 8) & 0xff);
_spi_write((ida >> 0) & 0xff);
CS_on;
}
void A7105_ReadID() {
uint8_t i;
CS_off;
_spi_write(0x46);
for (i = 0; i < 4; i++) {
aid[i] = _spi_read();
}
CS_on;
}
//----------------------
void Read_Packet() {
uint8_t i;
CS_off;
_spi_write(0x45);
for (i = 0; i < 21; i++) {
packet[i] = _spi_read();
}
CS_on;
}
//---------------------------------
//--------------------------------------
void _spi_write(uint8_t command) {
uint8_t n = 8;
SCK_off;//SCK starts low
SDI_off;
while (n--) {
if (command & 0x80)
SDI_on;
else
SDI_off;
SCK_on;
NOP();
SCK_off;
command = command << 1;
}
SDI_on;
}
void _spi_write_adress(uint8_t address, uint8_t data) {
CS_off;
_spi_write(address);
NOP();
_spi_write(data);
CS_on;
}
//-----------------------------------------
uint8_t _spi_read(void) {
uint8_t result;
uint8_t i;
result = 0;
//pinMode(SDI_pin, INPUT); //make SDIO pin input //ATMEGA328
PORTB.DIRCLR = PIN4_bm; //ATTINY1616 INPUT
//SDI_on;
for (i = 0; i < 8; i++) {
if (SDI_1) //if SDIO ==1
result = (result << 1) | 0x01;
else
result = result << 1;
SCK_on;
NOP();
SCK_off;
NOP();
}
//pinMode(SDI_pin, OUTPUT); //make SDIO pin output again //ATMEGA328
PORTB.DIRSET = PIN4_bm; //ATTINY1616 OUTPUT
return result;
}
//--------------------------------------------
uint8_t _spi_read_adress(uint8_t address) {
uint8_t result;
CS_off;
address |= 0x40;
_spi_write(address);
result = _spi_read();
CS_on;
return (result);
}
//------------------------
void _spi_strobe(uint8_t address) {
CS_off;
_spi_write(address);
CS_on;
}
//------------------------
void A7105_reset(void) {
_spi_write_adress(0x00, 0x00);
}