Hi everyone.
So, let’s solve the problem of MERIDIAN FLIP
This code and diagram that you will find below is fully functional with the Satnogs rotor both V.2 and V.3 and uses an ARDUINO UNO R3, two stepper drivers a4988 and three buttons for manual control of the rotor (UP - DOWN and CHANGE MOTOR AZ / EL).
They work very well with RS232 / TTL FTDI CHIP and can be made on breadboards.
The code written by IK5XWA Francesco Bandini who sent me months ago, I modified and adapted it for our Satnogs rotator, with a ratio of 54: 1 (but it is editable for any relationship), works in FULL STEP, but you can set also for half step and more.
In addition I implemented the two-line display that displays the position reached and to be reached.
This code solves the MERIDIAN FLIP problem in this part
// ------------------------------------------------ ------------
int rotate_elevaz (int el_val)
{
float eps; // difference in degrees between posiz. volute and current
int nstep; // no. of steps to request from the engine
eps = el_val - el_att; // calculate position error
nstep = round (eps * (float) ((STEPS / 360.0)));
if (abs (nstep)> = 2) // if the steps are few, it does not execute them
{
if (idebug & 4)
{
Serial.print (“move rotor ELEVATION: nstep =”);
Serial.println (nstep);
pause();
} // fine if idebug
step_el (nstep); // if non-zero error moves motor
el_att = el_val; // open ring: assumes to have reached the pos. volute
} // end if abs (nstep> = 2)
return el_att;
} // end rotate_elevaz
// ------------------------------------------------ --------------
#include <LiquidCrystal_I2C.h>
#include <Wire.h>
LiquidCrystal_I2C lcd(0x27,16,2);
//------------------------------------------------------------------
// Codice C++ di Francesco Bandini IK5XWA -
// Revisione codice per rotore Satnogs V2 - IZ5RZR Caturegli Massimiliano
// Routine che riceve dati di Azimuth ed Elevazione dal programma
// Orbitron, e pilota un rotore emulando il protocollo Yaesu GS-232
// Il rotore e' realizzato con due motori a passo NEMA17
// pilotati da drivers Pulse/Direction Allegro A4988
// Versione per Arduino Uno (libreria SoftwareSerial)
// usa pin 9 (TX1) e pin 10 (RX1) di Arduino Uno per la seriale
// il software presuppone che allo start (o dopo un reset) l'azimuth
// sia = zero (antenna verso Nord) e l'elevazione sia = zero (anten-
// na orizzontale)
//------------------------------------------------------------------
//To enable Display 16x2 connect +5v display to +5v arduino; pin Gnd display to Gnd arduino also pin SCL and SDA to Arduino pin A5 and pin A4:
#include <SoftwareSerial.h> // questo serve per Arduino UNO
SoftwareSerial Serial1(9,10); // 9=TX, 10= RX
#define STEPS 10800 // valore 4146 perchè 360/1.8 = passi per giro dello stepper
// moltiplicati per 54 (rapporto del riduttore Satnogs V3) se Satnogs V1 il rapporto gear ratio è 60 invece
// moltiplicato poi anche per il fattore di microstep (4), quindi 43200 se v.3 con 1/4 step se fullstep allore è 10800
// NOTA: le variabili az_att e el_att vengono inizializzate a zero
// solo qui. Per cui dopo un posizionamento manuale (antenna
// verso Nord ed elevazione = 0) va fatto un reset di Arduino
int az_att = 0; // inizializza posiz. attuale azimuth
int az_val = 0;
int el_att = 0; // inizializza posiz. attuale elevazione
int el_val = 0;
// variabili per lettura da porta RS232
byte serial_buffer[64];
int serial_buffer_index = 0;
int parsed_elevation = 0; // var rese da serial_command
int parsed_azimuth = 0;
//-------- sezione per drivers Allegro A4988
// Current limiting
// The A4988 supports such active current limiting, and the
// trimmer potentiometer on the board can be used to set the
// current limit. One way to set the current limit is to put
// the driver into full-step mode and to measure the current
// running through a single motor coil without clocking the STEP
// input. The measured current will be 0.7 times the current
// limit (since both coils are always on and limited to 70% of
// the current limit setting in full-step mode).
// Please note that changing the logic voltage, Vdd, to a
// different value will change the current limit setting since
// the voltage on the “ref” pin is a function of Vdd.
// Note: The coil current can be very different from the power
// supply current, so you should not use the current measured at
// the power supply to set the current limit.
// The appropriate place to put your current meter is in series
// with one of your stepper motor coils.
// Setting dei pin collegati ad Allegro A4988:
// motore 0 : Step=4, Dir=5 (azimuth)
// motore 1 : Step=6, Dir=7 (elevazione)
int StepPin[2] = {4,6}; // STEP pin motori 0 e 1
int DirPin[2] = {5,7}; // DIR pin motori 0 e 1
// i pin per il microstepping invece sono in comune
int MS1Pin = 11; // MS1 pin di Allegro (Microstep)
int MS2Pin = 12; // MS2
int MS3Pin = 13; // MS3
// Please note that the RST pin is floating; if you are not
// using the pin, you can connect it to the adjacent SLP pin
// on the PCB to bring it high and enable the board.
// ------sezione per il comando manuale dei motori-----
// Most Arduino boards have two external interrupts:
// numbers 0 (on digital pin 2) and 1 (on digital pin 3).
// The Arduino Mega has an additional four: numbers 2 (pin 21),
// 3 (pin 20), 4 (pin 19), and 5 (pin 18).
// il pulsante di cambio motore va sul pin digitale 3
// di arduino, che e' quello che genera l'interrupt 1
const int MotorSwitchPin = 3; // Pulsante cambio motore
// NumMotor verra' cambiata all'interno della routine
// di interrupt, per cui va dichiarata volatile
volatile int NumMotor = 0;
int MotorDirection = 1; // 1 = FWD, 0 = REV
// speed_az e' il ritardo in millisecondi tra un impulso e il
// successivo. Quindi vel. max = delay(1) e vel. min = delay(10)
float speed_az = 1.0; // fattore di velocita' azimuth
float speed_el = 1.0; // fattore velocita' elevazione
const int Move_FWD_Pin = 8; // pulsante di rotazione avanti
const int Move_REV_Pin = 2; // Pulsante di rotazione indietro
// idebug & 1 per attivare pausa attendi un tasto...
// 2 attiva stampe rotazione elevazione
// 4 attiva stampe rotazione azimuth
// 8 Attiva stampe ricezione da COM4
// 16 Attiva stampe pulsanti comando manuale
int idebug = 0;
void setup()
{
// settaggi per ricezione da seriale RS232
// ricordarsi che l'uscita seriale RS-232 del PC e la Seriale TTL di Arduino NON sono collegabili direttamente
// va interposto un convertitore di livelli logici da RS232 a TTL, tipo l'integrato MAX232 che inverte lo stato logico
// e riporta i livelli da RS232 (+/- 13V) a TTL (0/+5V) - Senno' si rischia anche di bruciare Arduino
lcd.init();// inizializza il display
lcd.backlight();//accende la retroilluminazione
lcd.setCursor(0, 0); // set the cursor to column 0, line 0
lcd.print("IZ5RZR CtrlBox");
lcd.setCursor(0, 1); // set the cursor to column 0, line 1
lcd.print("WWW.CATUREGLI.IT");
delay(4000);
lcd.clear();
Serial1.begin(9600); // usa pin 9 (TX1) e pin 10 (RX1) di Arduino Uno
Serial.begin(9600); // the SerialMonitor baud rate
delay(100);
if (idebug & 8)
{
// tutto quello che arriva dalla RS232 viene visualizzato
// anche sulla seriale monitor di Arduino
lcd.setCursor(0, 0); // set the cursor to column 0, line 0
Serial.println("ricezione da Seriale 1 attivata...");
} // fine if idebug
setSpeed_az(50); // set velocita' azimuth (1 min - 100 max) 50 def
setSpeed_el(50); // set velocita' elevazione
az_att = 0;
el_att = 0;
// ------ sezione per driver Allegro A4988
for (int i=0; i<2; i++)
{
pinMode(StepPin[i], OUTPUT);
pinMode(DirPin[i], OUTPUT);
digitalWrite(DirPin[i],HIGH); // inizializza direzione
} // next i
pinMode(MS1Pin, OUTPUT);
pinMode(MS2Pin, OUTPUT);
pinMode(MS3Pin, OUTPUT);
pinMode(Move_REV_Pin,INPUT);
pinMode(Move_FWD_Pin,INPUT);
// Aggancia interrupt ai pulsanti di comando manuale:
// dal reference manual di attachInterrupt:
// LOW to trigger the interrupt whenever the pin is low,
// CHANGE to trigger the interrupt whenever the pin changes value
// RISING to trigger when the pin goes from low to high,
// FALLING for when the pin goes from high to low.
// normalmente il pin 3 (cambio motore) e' tenuto LOW dalla resistenza di
// pull-down (vedi schema 27/12/2014), e diventa HIGH quando
// si preme il pulsante che lo porta a +5 Volts
attachInterrupt(1, changeMotor, RISING);
//---------------------------------------------
// MS1 MS2 MS3 Microstep Resolution
// Low Low Low Full step
// High Low Low Half step
// Low High Low Quarter step
// High High Low Eighth step
// High High High Sixteenth step
digitalWrite(MS1Pin,LOW);
digitalWrite(MS2Pin,LOW);
digitalWrite(MS3Pin,LOW);
// attenzione che se cambi lo stepping la costante
// STEPS definita all'inizio non va piu' bene
//------fine sezione drive Allegro
} // fine setup
void loop()
{
// controlla pressione tasti di posizionamento manuale
// la variabile NumMotor viene cambiata tra 0 e 1 nella
// routine interrupt changeMotor, chamata dal pulsante 3
if (digitalRead(Move_FWD_Pin) == HIGH) // premuto tasto FWD
{
if (MotorDirection != 1)
{
MotorDirection = 1;
digitalWrite(DirPin[NumMotor],HIGH);
} // fine if MotorDirection != 1
// manda impulsi al driver
digitalWrite(StepPin[NumMotor],HIGH);
delay(2);
digitalWrite(StepPin[NumMotor],LOW);
delay(2);
} // fine if pulsante FWD premuto
if (digitalRead(Move_REV_Pin) == HIGH) // premuto tasto REV
{
if (MotorDirection != 0)
{
MotorDirection = 0;
digitalWrite(DirPin[NumMotor],LOW);
} // fine if MotorDirection != 0
// manda impulsi al driver
digitalWrite(StepPin[NumMotor],HIGH);
delay(2);
digitalWrite(StepPin[NumMotor],LOW);
delay(2);
} // fine if pulsante REV premuto
// le variabili parsed_azimuth e parsed_elevation
// vengono settate dalla routine serial_command che
// legge il comando che arriva da Orbitron via RS232
az_val = 0;
el_val = 0;
int ivalid = serial_command(); // legge comando Wxxx yyy
if (ivalid)
{
lcd.setCursor(0, 0); // set the cursor to column 0, line 0
lcd.print("Azimuth=");
lcd.print(parsed_azimuth);
lcd.print("->");
lcd.print(az_att);
lcd.print(" ");
Serial.print(" Azimuth letto: ");
Serial.print(parsed_azimuth);
Serial.print(" attuale = ");
Serial.print(az_att);
lcd.setCursor(0, 1); // set the cursor to column 0, line 0
lcd.print("Elevation=");
lcd.print(parsed_elevation);
lcd.print("->");
lcd.print(el_att);
lcd.print(" ");
Serial.print(" - Elevazione letta: ");
Serial.print(parsed_elevation);
Serial.print(" attuale = ");
Serial.println(el_att);
if (parsed_elevation > 0) // il satellite appare all'orizzonte
{
az_val = parsed_azimuth;
el_val = parsed_elevation;
Serial.print("--> chiamo routines di posiz: AZ = ");
Serial.print(az_val);
Serial.print(" EL = ");
Serial.println(el_val);
pausa();
rotate_azimuth(az_val); // aggiorna az_att in common
el_att = rotate_elevaz(el_val);
Serial.print("Dopo routines di posiz: AZ = ");
Serial.print(az_att);
Serial.print(" EL = ");
Serial.println(el_att);
} // fine if parsed_elevation > 0
} // fine if ivalid
} // fine loop principale
//-------------------------------------------------------------
// routines di servizio
//-------------------------------------------------------------
//The flip meridian solution
// IK5XWA wrote per fare questo collegamento ho fatto una piccola ottimizzazione al codice, per evitare che l'antenna faccia una rotazione completa da 360 a zero quando la traiettoria attraversa il nord: devi sostituire la funzione rotate_azimuth con questa:
//-------------------------------------------------------------
void rotate_azimuth(int az_val)
{
float eps; // differenza in gradi tra posiz. voluta e attuale
int nstep; // no. di step da richiedere al motore
eps = az_val - az_att; // calcola errore di posizione
// notare che az_val (e quindi anche az_att) sono sempre tra 0 e 360
if (fabs(eps) > 180.) // deve fare piu' di mezzo giro
{
if (az_att < 180)
{
// esempio: deve andare da +10 a +350, eps diventa (350 - 360) -10 = -20 e gira al contrario
eps = (az_val - 360) - az_att;
}
else // az_att > 180
{
// ha passato il nord girando in senso orario (esempio az_att = 350 e az_val = 10)
eps = az_val -(az_att - 360); // 10 - (350 - 360) = +20 e continua in senso orario
} // end if az_att > 180
} // end if fabs(eps) > 180
nstep = round(eps * (float)((STEPS / 360.0)));
if (abs(nstep) >= 2) // se gli step sono pochi non li esegue
{
step_az(nstep); // se errore non zero muove motore
az_att = az_val; // anello aperto:assume di aver raggiunto la pos. voluta
} // fine if abs(nstep >= 2)
} // fine rotate_azimuth
// Ti consiglio di farlo perche' senno' rischi, durante un collegamento vero, di perdere il contatto col satellite ogni volta che passa dal Nord. Francesco IK5XWA
//------------------------------------------------------------
int rotate_elevaz(int el_val)
{
float eps; // differenza in gradi tra posiz. voluta e attuale
int nstep; // no. di step da richiedere al motore
eps = el_val - el_att; // calcola errore di posizione
nstep = round(eps * (float)((STEPS / 360.0)));
if (abs(nstep) >= 2) // se gli step sono pochi non li esegue
{
if (idebug & 4)
{
Serial.print(" muovo rotore ELEVAZIONE: nstep = ");
Serial.println(nstep);
pausa();
} // fine if idebug
step_el(nstep); // se errore non zero muove motore
el_att = el_val; // anello aperto: assume di aver raggiunto la pos. voluta
} // fine if abs(nstep >= 2)
return el_att;
} // fine rotate_elevaz
//--------------------------------------------------------------
void pausa() // aspetta un tasto
{
if (!(idebug & 1))
return;
Serial.println(" premi un tasto... ");
while (Serial.available() == 0)
{}
while (Serial.available())
char aa=Serial.read(); // svuota buffer seriale
} // fine pausa
// -------------------------------------------------------------------
// clear_buffer
//--------------------------------------------------------------------
void clear_buffer()
{
serial_buffer_index=0; // riazzera contatore caratteri ricevuti
serial_buffer[0]=0;
} // fine clear_buffer
// -------------------------------------------------------------------
// read_Serial preleva la stringa in arrivo dalla seriale RS232
// rende il numero dei bytes letti e mette la stringa nel buffer
//--------------------------------------------------------------------
int read_serial()
{
int incoming_byte=0;
int incomingBytes=Serial1.available();
if (incomingBytes > 0)
{
if (idebug & 8)
{
Serial.print("Ricevuti ");
Serial.print(incomingBytes);
Serial.println(" bytes : ");
} // fine if idebug
// read the incoming bytes:
for (int i=1; i<=incomingBytes; i++)
{
incoming_byte = Serial1.read();
serial_buffer[serial_buffer_index] = incoming_byte;
serial_buffer_index++;
delay(10);
if (idebug & 8)
{
// say what you got:
Serial.print(incoming_byte,DEC);
Serial.print(" ");
Serial.println((char) incoming_byte);
} // fine if idebug
} // next i
} // fine if incomingBytes > 0
serial_buffer[serial_buffer_index]=0; // mette terminatore alla stringa buffer
return incomingBytes;
} // fine read_serial
//----------------------------------------------------------
// serial_command legge comando Wxxx yyy e lo analizza
// rende parsed_azimuth e parsed_elevation (common)
//----------------------------------------------------------
int serial_command()
{
clear_buffer(); // svuota buffer seriale
int incomingBytes = 0;
incomingBytes=read_serial(); // legge stringa in arrivo da Seriale 1
if (incomingBytes == 1) // e' un comando W?
{
if (serial_buffer[0] == 'W') // e' un comando Wxxx yyy
{
if (idebug & 8)
Serial.println(F("serial_command: W cmd"));
incomingBytes=read_serial(); // legge il resto del comando
if (incomingBytes == 8)
{
// analisi della stringa buffer per estrarre Azimuth ed elevazione
// i comandi arrivano nella forma Wxxx yyy dove xxx = Azimuth, yyy = Elevazione in gradi
parsed_azimuth = (((int(serial_buffer[1])-48)*100) + // centinaia
((int(serial_buffer[2])-48)*10) + // decine
(int(serial_buffer[3])-48)); // unita'
// salta lo spazio tra xxx ed yyy
parsed_elevation = (((int(serial_buffer[5])-48)*100) +
((int(serial_buffer[6])-48)*10) +
(int(serial_buffer[7])-48));
} // fine if incomingBytes == 8 (xxx yyy)
} // fine if serial_buffer[0] == 'W'
else // non e' un comando W
{
if (idebug & 8)
{
Serial.print("serial_command: ");
Serial.print(serial_buffer[0]);
Serial.println(" comando non riconosciuto!!");
} // fine if idebug
} // fine if not comando W
clear_buffer(); // svuota buffer seriale
} // fine if incomingBytes == 1 (comando W)
return incomingBytes;
} // fine serial_command
//---- routines per comando motori
void setSpeed_az(int factor)
{
// speed_az e' il ritardo in millisecondi tra un impulso e il
// successivo. Quindi vel. max = delay(1) e vel. min = delay(100) ***** qui va modificata la velocitĂ di movimento motori
speed_az = 66.0 - factor;
if (speed_az < 1) speed_az = 1;
} // fine setSpeed_az
void setSpeed_el(int factor)
{
speed_el = 68.0 - factor;
if (speed_el < 1) speed_el = 1;
} // fine setSpeed_el
void step_az(int nstep)
{
// ad un azimuth positivo corrisponde
// una rotazione oraria
if (nstep < 0) // deve tornare indietro
{
digitalWrite(DirPin[0],LOW); // antiorario
nstep = -nstep;
}
else // rotazione positiva
{
digitalWrite(DirPin[0],HIGH);
} // fine if nstep > 0
delay(10);
int millis_delay = speed_az;
// se la rotazione e' maggiore di 90 gradi, o e' il
// posizionamento iniziale o e' il riposizionamento
// di 360 che fa quando attraversa il Nord, per cui
// lo fa in rapido
if (nstep > STEPS/4.) // riposizionamento rapido
millis_delay=1;
// manda impulsi al driver
for (int i=0; i<nstep; i++)
{
digitalWrite(StepPin[0],HIGH); // motore 0 = azimuth
delay(millis_delay);
digitalWrite(StepPin[0],LOW);
delay(millis_delay);
} // next i
} // fine step_az
//-----------------------------------------------------
void step_el(int nstep)
{
// ad una elevaz. positiva corrisponde
// una rotazione oraria e viceversa
if (nstep < 0) // deve tornare indietro
{
digitalWrite(DirPin[1],LOW); // antiorario
delay(5);
nstep = -nstep;
if (idebug & 4)
{
Serial.print("Rotazione ANTIORARIA: nstep = ");
Serial.println(nstep);
}
}
else // rotazione positiva
{
digitalWrite(DirPin[1],HIGH); // orario
delay(5);
if (idebug & 4)
{
Serial.print("Rotazione ORARIA: nstep = ");
Serial.println(nstep);
}
} // fine if nstep > 0
// manda impulsi al driver
for (int i=0; i<nstep; i++)
{
digitalWrite(StepPin[1],HIGH); // motore 1 = elevazione
delay(speed_el);
digitalWrite(StepPin[1],LOW);
delay(speed_el);
} // next i
} // fine step_el
//-------------------------------------------------------------
//---routines di rilevamento interrupt - comando manuale motori
//-------------------------------------------------------------
void changeMotor() // chiamata sul fronte di salita del pin 3
{
// entra qui quando la pressione del pulsante fa diventare HIGH
// il pin 3, a cui e' attaccato l'interrupt 1
// NOTE: Inside the attached function, delay() won't work
// and the value returned by millis() will not increment.
// Serial data received while in the function may be lost.
// You should declare as volatile any variables that you
// modify within the attached function.
if (NumMotor == 1)
NumMotor = 0; // motore azimuth
else
NumMotor = 1; // motore elevazione
if (idebug & 16)
{
Serial.println("");
Serial.print("Cambiato motore! ora e' = ");
Serial.println(NumMotor);
}
} // fine changeMotor
/*-----------------------------------------------
int round(float number)
{
return (number >= 0) ? (int)(number + 0.5) : (int)(number - 0.5);
}
//-----------------------------------------------*/
here the electronic scheme
scansione.pdf (4.0 MB)