Arduino mega alimentato con batt 8,4v
Il codice non gira se non è collegata anche usb 5v
Il codice parte ma si inceppa subito
Grazie
Marco
vedere il codice aiuterebbe molto
magari nel setup hai lasciato il while(!Serial) ;
NO nid, sei su una MEGA, non c'è USB nativa, quindi quel while sarebbe immediatamente soddisfatto.
Inoltre NON si capisce cosa succede ...
... che vuol dire? Dove esattamente si blocca? ... tocca fare DEBUG e capire il punto esatto in cui si blocca e, ovviamente, come dice Ducembarr, occorre vedere il codice.
Guglielmo
Nell'attesa del codice, invochiamo tutti San Ceppato!
8,4V dove? Vin? Lo "spinotto"? Arduino Mega originale o clone?
Ci sono troppe lacune...
Alimentazione instabile...
Tradotto, la batteria è scarica.
Batteria NIMH 4000 ma 8,4v carica e collegata allo spinotto
Il codice stampa su oled "AC75" poi si spegne e tutto si blocca
L'applicazione è un flight controller per barche a vela AC75 [AC75_v1_5_REL_03.ino|attachment](upload://zUfmJSVpOYWEz44V02QuNCsuQj4.ino) (12,8 KB) Marco
/*
AC75 - Control firmware
Vers. 1.5 - Rel. 03
Date 22/04/2024
DynArts
*/
//#include <SoftwareSerial.h>
#include <Servo.h>
#include <Wire.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include <YetAnotherPcInt.h>
#include <arduino-timer.h>
/** PIN ASSIGNMENT **/
#define MANUAL_1 A8 // Port PK0 - Input PWM channel from radio receiver (Manual 1) - CH10 VrD
#define MANUAL_2 A9 // Port PK1 - Input PWM channel from radio receiver (Manual 2) - CH8 VrE
#define SETPOINT A10 // Port PK2 - Input PWM setpoint height from radio receiver - CH3 Stick 3 (sx w/o spring)
#define GAIN_1 A11 // Port PK3 - Input PWM channel from radio receiver (Foil 1 gain) - CH6 VrA
#define GAIN_2 A12 // Port PK4 - Input PWM channel from radio receiver (Foil 2 gain) - CH7 VrC
#define GAIN_3 A13 // Port PK5 - Input PWM channel from radio receiver (Rudder gain) - CH9 VrB
#define ECHO_1 A14 // Port PK6 - Input echo Sonar 1
#define ECHO_2 A15 // Port PK7 - Input echo Sonar 2
#define MODE 53 // Port PB0 - Switch from manual to auto - PCINT0 - CH11 SwB
#define FOIL_1 44 // Port PL5 - Servo 1 PWM driver output
#define FOIL_2 45 // Port PL4 - Servo 2 PWM driver output
#define TRIG_1 48 // Port PL1 - Sonar 1 trigger output
#define TRIG_2 49 // Port PL0 - Sonar 2 trigger output
/** OLED CONSTANTS **/
#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
// Declaration for an SSD1306 display connected to I2C (SDA, SCL pins)
// The pins for I2C are defined by the Wire-library.
// On an arduino UNO: A4(SDA), A5(SCL)
// On an arduino MEGA 2560: 20(SDA), 21(SCL)
// On an arduino LEONARDO: 2(SDA), 3(SCL), ...
#define OLED_RESET -1 // Reset pin # (or -1 if sharing Arduino reset pin)
#define SCREEN_ADDRESS 0x3C ///< See datasheet for Address; 0x3D for 128x64, 0x3C for 128x32
#define ARRAY_SIZE(X) (sizeof(X)/sizeof(*X))
#define P_CONV(T) (p_m*T+p_q)
#define H_CONV(T) (h_m*T+h_q)
/*
Verificare:
1. Utilizzare controller servo anche in canali con timer 8 bit ed eventualmente spostare
2. Misura di OnTime da interrupt anche su canali con timer 8 bit
*/
/********************/
/**** CONTROL CONSTANTS *****/
#define SONAR_WMF_DEPTH 5 // samples
#define SOUND_SPEED 348 // um/s
#define SOUND_SPEED_UM_S 0.0348 // um/s
#define EXPECTED_DISTANCE 20.0 // cm
#define TAIL_SIGMA 10.0 // cm
#define P_MIN 0.0 // Min potentiometer value (%)
#define P_MAX 100.0 // Max potentiometer value (%)
#define H_MIN 4.0 // Min distance
#define H_MAX 40.0 // Max distance
#define TON_VRX_MIN 916 // Min pulse width for Vr (us)
#define TON_VRX_MAX 2112 // Max pulse width for Vr (us)
#define TON_STX_MIN 1068 // Min pulse width for Stick (us)
#define TON_STX_MAX 1976 // Max pulse width for Stick (us)
#define KP0 5 // Auto mode: Regulator proportional pre-gain factor. Kp=g*KP0 [°/m]
#define KD0 1 // Auto mode: Regulator derivative factor
#define MIN_ANGLE 1 // Min permitted servo angle
#define MAX_ANGLE 189 // Max permitted servo angle
//Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RESET);
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT);
/********************/
/**** Variables *****/
float p_m, p_q;
float h_m, h_q;
float Kp; // Kp=g*KP0 [°/m]
float Kd = KD0;
float g[3];
float e;
float setpoint;
int mode; // Mode selection channel - SwC:: OFF:1070ms, ON:1940
float foilAngle; // Foil servo angle
int angle[2];
int alpha1, alpha3;
float alpha2;
Servo foilServo[2];
Timer<2> sonarTrigger;
/********* input PWM duration ***************/
struct pinTime
{
uint8_t index;
uint8_t pinNumber;
const char* name;
unsigned long Tstart;
unsigned long Tstop;
unsigned long delta;
float result;
};
// List of monitored pins inputCtrl
static pinTime inputCtrl[] =
{
{ 0, MODE, "Mode (SwB)", 0, 0, 0, 0 },
{ 1, MANUAL_1, "Manual 1 (VrD)", 0, 0, 0, 0 },
{ 2, MANUAL_2, "Manual 2 (VrE)", 0, 0, 0, 0 },
{ 3, GAIN_1, "Gain 1 (VrA)", 0, 0, 0, 0 },
{ 4, GAIN_2, "Gain 2 (VrC)", 0, 0, 0, 0 },
{ 5, GAIN_3, "Gain 3 (VrB) NC",0, 0, 0, 0 },
{ 6, SETPOINT, "Setpoint (St3)", 0, 0, 0, 0 },
};
// List of monitored pins sonar
static pinTime sonar[] =
{
{ 0, ECHO_1, "Sonar 1", 0, 0, 0, 0 },
{ 1, ECHO_2, "Sonar 2", 0, 0, 0, 0 },
};
float sonarStats[2][2]; // [ 0: Sonar1, 1: Sonar2 ] [ 0: mean, 1: derivative ]
float distanceBuffer[2][SONAR_WMF_DEPTH+1] = {0}; // [ 0: Sonar1, 1: Sonar2 ] [circular buffer pointer]
/**********************************************/
/**** Funcions prototypes *****/
void updateSonarStats(uint8_t index);
void updateInputOnTime(pinTime* pin, bool pinstate);
void updateSonarOnTime(pinTime* pin, bool pinstate);
void sonarLaunch();
/******************************/
void setup()
{
// Terminal and serial commands
Serial.begin(115200);
pinMode(MANUAL_1, INPUT);
pinMode(MANUAL_2, INPUT);
pinMode(GAIN_1, INPUT);
pinMode(GAIN_2, INPUT);
pinMode(GAIN_3, INPUT);
pinMode(SETPOINT, INPUT);
pinMode(MODE, INPUT);
pinMode(TRIG_1, OUTPUT); digitalWrite(TRIG_1, LOW);
pinMode(TRIG_2, OUTPUT); digitalWrite(TRIG_2, LOW);
/***** Setup INPUT CONTROL interrupts *****/
for (int i=0; i<ARRAY_SIZE(inputCtrl); i++)
{
pinMode( inputCtrl[i].pinNumber, INPUT );
PcInt::attachInterrupt( inputCtrl[i].pinNumber, updateInputOnTime, &inputCtrl[i], CHANGE );
}
/***** Setup SONAR CONTROL interrupts *****/
for (int i=0; i<ARRAY_SIZE(sonar); i++)
{
pinMode( sonar[i].pinNumber, INPUT );
PcInt::attachInterrupt( sonar[i].pinNumber, updateSonarOnTime, &sonar[i], CHANGE );
}
foilServo[0].attach(FOIL_1);
foilServo[1].attach(FOIL_2);
p_m = (P_MAX-P_MIN) / (TON_VRX_MAX-TON_VRX_MIN);
p_q = P_MAX - p_m * TON_VRX_MAX;
h_m = (H_MAX-H_MIN) / (TON_STX_MAX-TON_STX_MIN);
h_q = H_MAX - h_m * TON_STX_MAX;
sonarTrigger.every(20, sonarLaunch);
/********** OLED setup **********/
if (!display.begin( SSD1306_SWITCHCAPVCC, 0x3C) ) while (true);
display.clearDisplay();
display.display();
display.setTextColor(WHITE);
display.setTextSize(4);
display.setCursor(0, 0);
display.println(" AC75 ");
display.display();
// Send msg to set the contrast --- function: display.ssd1306_command(uint8_t c)
display.ssd1306_command( SSD1306_SETCONTRAST ); // Develop
display.ssd1306_command( 0xFF );
delay(1000);
display.clearDisplay();
display.setTextSize(2);
display.setCursor(0, 0);
}
void loop()
{
auto ticks = sonarTrigger.tick();
//Serial.println( "Ticks 0 " + String(ticks) );
//sonarLaunch();
mode = P_CONV( float(inputCtrl[0].delta) ) -50;
g[0] = P_CONV( float(inputCtrl[3].delta) );
g[1] = P_CONV( float(inputCtrl[4].delta) );
g[2] = P_CONV( float(inputCtrl[5].delta) );
setpoint = H_CONV( float(inputCtrl[6].delta) );
display.clearDisplay();
display.setCursor(0, 0);
display.println( "G1 " + String(g[0],0) + "\nG2 " + String(g[1],0) + "\nG3 " + String(g[2],0) + "\nSET " + String(setpoint,0) );
display.display();
/*
Serial.println( "\t" + String(inputCtrl[0].name) + " " + String(mode) +
"\t" + String(inputCtrl[1].name) + " " + String(inputCtrl[1].delta) +
"\t" + String(inputCtrl[2].name) + " " + String(inputCtrl[2].delta) +
"\t" + String(inputCtrl[3].name) + " " + String(g[0]) +
"\t" + String(inputCtrl[4].name) + " " + String(g[1]) +
"\t" + String(inputCtrl[5].name) + " " + String(g[2]) +
"\t" + String(inputCtrl[6].name) + " " + String(setpoint)
);
*/
/*
Serial.println();
for (uint8_t i=0; i<7; i++)
{
Serial.print( "\t" + String(inputCtrl[i].name) + "\t" + String(inputCtrl[i].delta) );
}
//Serial.println();
*/
/*
Serial.println( "\t" + String(sonar[0].name) + " " + String( sonarStats[0][0]) + " " + String(sonarStats[0][1]) +
"\t" + String(sonar[1].name) + " " + String( sonarStats[1][0]) + " " + String(sonarStats[1][1])
);
*/
//mode=1;
if (mode>0)
{
ticks = sonarTrigger.tick();
//Serial.println( "Ticks 1 " + String(ticks) );
//Serial.println( "Setpoint = " + String(setpoint) + " cm" );
Serial.print( "SP=" + String(setpoint) );
for (uint8_t i=0; i<2; i++)
{
ticks = sonarTrigger.tick();
//Serial.println( "Ticks 2 " + String(ticks) );
//Kp = KP0 * g[i];
Kp = KP0; // Regolatore indipendente dal gain
Kd = KD0;
e = setpoint - sonarStats[i][0];
ticks = sonarTrigger.tick();
//Serial.println( "Ticks 3 " + String(ticks) );
/* Angle regulator */
float delta = Kp*e + Kd*abs( sonarStats[i][1] );
angle[i] -= delta;
alpha1 = angle[i] -90;
alpha2 = g[i]*alpha1/100.0;
alpha3 = alpha2 +90;
angle[i] = alpha3;
if(angle[i]<=MIN_ANGLE) angle[i] = MIN_ANGLE;
if(angle[i]>=MAX_ANGLE) angle[i] = MAX_ANGLE;
ticks = sonarTrigger.tick();
//Serial.println( "Ticks 4 " + String(ticks) );
Serial.print( "\tAXIS_" + String(i+1) + "\tD = " + String(sonarStats[i][0]) +
"\te=" + String(e) + "\treg=" + String(Kp*e) + "\tangle=" + String(angle[i]) + "\tG=" + String(g[i]) );
ticks = sonarTrigger.tick();
//Serial.println( "Ticks 5 " + String(ticks) );
foilServo[i].write(angle[i]);
}
Serial.println();
}
else
{
Serial.println();
for (uint8_t i=0; i<2; i++)
{
for (uint8_t j=0; j<7; j++)
{
Serial.print( "\t" + String(inputCtrl[j].name) + "\t" + String(inputCtrl[j].delta) );
}
foilServo[i].write(inputCtrl[i+1].delta);
angle[i] = foilServo[i].read();
Serial.println("\tServo " + String(i+1) + " angle = " + String(angle[i]) );
}
//Serial.println();
}
}
/*** Functions definition ***/
void updateSonarStats(uint8_t index)
{
unsigned int reading;
static uint8_t crp;
float mean = 0.0;
float der = 0.0;
uint8_t i=0;
crp = distanceBuffer[index][SONAR_WMF_DEPTH];
distanceBuffer[index][crp] = sonar[index].result;
uint8_t lastSample_crp = crp;
crp++;
crp = crp%SONAR_WMF_DEPTH;
uint8_t firstSample_crp = crp;
distanceBuffer[index][SONAR_WMF_DEPTH] = crp;
for (i=0; i < SONAR_WMF_DEPTH; i++)
{
float f = distanceBuffer[index][i];
float w = 1 + abs(f - sonarStats[index][0] );
//Serial.println(f/w);
//mean += f/w;
mean += f;
//Serial.println(mean);
}
mean = mean / SONAR_WMF_DEPTH;
//Serial.println(mean);
int delta = distanceBuffer[index][lastSample_crp] - distanceBuffer[index][firstSample_crp];
der = ( delta ) / SONAR_WMF_DEPTH;
sonarStats[index][0] = mean;
sonarStats[index][1] = der;
return;
}
/****** ISR definitions **********/
void updateInputOnTime(pinTime* pin, bool pinstate)
{
if( pinstate )
{
pin->Tstart = micros();
//Serial.print(pin->name); Serial.print(" Tstart = "); Serial.print(pin->Tstart); Serial.print("\n");
}
else
{
pin->Tstop = micros();
pin->delta = ( pin->Tstop - pin->Tstart );
//Serial.print(pin->name); Serial.print(" Tstop = "); Serial.print(pin->Tstop); Serial.print("\n");
//Serial.print(pin->name); Serial.print(" Delta =\t"); Serial.print(pin->delta); Serial.print("\n");
}
}
void sonarLaunch()
{
digitalWrite(TRIG_1, HIGH);
digitalWrite(TRIG_2, HIGH);
delayMicroseconds(30);
digitalWrite(TRIG_1, LOW);
digitalWrite(TRIG_2, LOW);
//Serial.println("Trig millis " + String(millis()) );
}
void updateSonarOnTime(pinTime* pin, bool pinstate)
{
//Serial.println("ISR");
if( pinstate )
{
pin->Tstart = micros();
//Serial.println( String(pin->name) + " Tstart = " + String(pin->Tstart) );
}
else
{
pin->Tstop = micros();
pin->delta = ( pin->Tstop - pin->Tstart );
pin->result = SOUND_SPEED_UM_S * pin->delta / 2;
//Serial.println( String(pin->name) + " Tstop = " + String(pin->Tstop) );
//Serial.println( String(pin->name) + " delta =\t" + String(pin->delta) );
//unsigned int T0 = micros();
//Serial.println( String(pin->name) + " delta =\t" + String(pin->delta) );
if ( pin->result < (EXPECTED_DISTANCE + TAIL_SIGMA) ) updateSonarStats( pin->index );
//sonarStats[ pin->index ] = updateSonarStats( pin->index );
//unsigned int T1 = micros();
//Serial.println("Cycle time = " + String(T1-T0) + "us" );
//Serial.println( String(pin->name) + " delta = " + String(pin->delta) );
}
return;
}
/*********************************/
Uno schema del circuito aiuterebbe, diciamo, per capire ad esempo come alimenti il display...
Se stai partendo da un progetto esistente, postane il link.
Se togli queste due righe, che succede?
display.ssd1306_command(SSD1306_SETCONTRAST); // Develop
display.ssd1306_command(0xFF);
Oled alimentato 5v - gnd Arduino
Cancellare le due righe non cambia
Marco
Scusa ma non è chiaro. "Alimentato 5V" che significa? Che lo alimenti dal pin 5V di Arduino?
E poi io nel codice metterei un po' di print di debug sulla seriale per capire se si blocca realmente, oppure se sta funzionando ma è l'output del display che non va.
L'idea di @Datman non era poi sbagliata, non so se per quel display "contrast" sia equivalente a "luminosità", ma al posto tuo proverei a scrivere un semplice sketch che va solo a scrivere qualcosa sull'oled nel setup e poi nel loop provare a variare questo "contrasto" diciamo da 50 a 255 a passi da 5 (diciamo ogni mezzo secondo) e vedere se cambia qualcosa, e fermarsi al valore che sembra funzionare.
Ma se non è questo, è un qualche altro problema, per me quello più probabile è l'alimentazione.
Si 5v di arduino
Non è solo il display, ma tutto è bloccato e se poi inserisco usb tutto si rimette a funzionare.
Quale può essere un problema di alimentazione? Come verificare? La batteria fornisce 8,8v.
Ho un altro arduino uno che funziona benissimo con lo stesso oled ed una batteriuccia non ricaricabile da 9v
Marco
Sotto carico o a vuoto?
Arduino mega prende input da una ricevente per aeromodelli e muove due servocomandi su input della trasmittente (manuale) oppure di due sonar (automatico).
Quando si blocca si blocca tutto
Marco
Quel pin può dare al massimo 500 mA se alimentato con l'USB altrimenti è 200 mA (massimo).
Lascia GND in comune ed alimenta il display direttamente con i 5V di un alimentatore (anche lo stesso che usi per Arduino, ma collegandolo a monte).
8,8v a vuoto
Marco
Ho disconnesso Oled ma non cambia nulla
Marco
E sotto carico?