Sunray modding Spielwiese

Suche mal nach Battery, da hat Einfach das Problem und eine Lösung für die Battery.cpp beschrieben. In der Version 298 gab es das Problem noch nicht. In der letzten Version besteht aber ein Ladeproblem. Kommt aufs Mainboard 1.4 oder 1.3 und ob gebrückt oder nicht drauf an.
Hatte gestern ein Update auf neuste Version gemacht und heute nur 24 Volt obwohl meine optischsche Ladekontrolle zeigte das er Charge enable hat.
Zurück auf die 298 und er lädt wieder voll.
https://forum.ardumower.de/threads/akku-wird-nicht-voll-geladen.25362/
thank you for the hint. I went through the battery.cpp to realize this batteryvoltageslope (problem in that topic) is not used anymore in this branch/fork :).
 
Hat leider nicht funktioniert danach hat er an der RunningMedian.h abgebroche.

In der Zwischenzeit habe ich mich nochmal mit der config.h vertraut gemacht und einige Formatierungen angepasst und überschüssige Zeichen entfernt.

Du kannst auch die aktuelle master nehmen, da ist die RC cpp aufgeräumt und ein Standard runningmedian wird verwendet, ohne das du eine Bibliothek brauchst. Allerdings brauchst du auch nicht so Vorsichtig sein, du kannst diesen include auch einfach auskommentieren.
 
thank you for the hint. I went through the battery.cpp to realize this batteryvoltageslope (problem in that topic) is not used anymore in this branch/fork :).
How so?

Look at battery.run(), just in the middle there is the slope.. :
Code:
void Battery::run(){
  if (startupPhase == 0) {
    // give some time to establish communication to external hardware etc.
    nextBatteryTime = millis() + 2000;
    startupPhase++;
    return;
  }
  if (millis() < nextBatteryTime) return; 
  nextBatteryTime = millis() + 50;
  if (startupPhase == 1) startupPhase = 2;

  // voltage
  float voltage = batteryDriver.getChargeVoltage();
  if (abs(chargingVoltage-voltage) > 10) {
    chargingVoltage = voltage;
    chargingVoltBatteryVoltDiff = 0;
  }
  chargingVoltage = 0.9 * chargingVoltage + 0.1* voltage;

  //actual_voltage = batteryDriver.getBatteryVoltage();
  //voltage = 0.1 * voltage + (1.0-0.1) * actual_voltage;
  voltage = batteryDriver.getBatteryVoltage();
  if (abs(batteryVoltage-voltage) > 10) {
    batteryVoltage = voltage;
    batteryVoltageLast = voltage;
    chargingVoltBatteryVoltDiff = 0;
  }
  float w = 0.995;
  if (chargerConnectedState) w = 0.9;
  batteryVoltage = w * batteryVoltage + (1-w) * voltage;

  // difference charging voltage and battery voltage
  chargingVoltBatteryVoltDiff = 0.99 * chargingVoltBatteryVoltDiff + 0.01 * (chargingVoltage - batteryVoltage);

  // current
  chargingCurrent = 0.9 * chargingCurrent + 0.1 * batteryDriver.getChargeCurrent(); 
  
  if (!chargerConnectedState){
      if (chargingVoltage > 7){
      chargerConnectedState = true;         
          DEBUG(F("CHARGER CONNECTED chgV="));                           
      DEBUG(chargingVoltage);   
      DEBUG(F(" batV="));
      DEBUGLN(batteryVoltage);
      buzzer.sound(SND_OVERCURRENT, true);     
    }
  }
  
  if (millis() >= nextCheckTime){ 
    nextCheckTime = millis() + 5000;                 
    if (chargerConnectedState){     
      if (chargingVoltage <= 5){
        chargerConnectedState = false;
        nextEnableTime = millis() + 5000;       // reset charging enable time           
        DEBUG(F("CHARGER DISCONNECTED chgV="));
        DEBUG(chargingVoltage);     
        DEBUG(F(" batV="));
        DEBUGLN(batteryVoltage);             
      }
    }           
    timeMinutes = (millis()-chargingStartTime) / 1000 /60;
    if (underVoltage()) {
      DEBUG(F("SWITCHING OFF (undervoltage) batV="));
      DEBUG(batteryVoltage);
      DEBUG("<");
      DEBUGLN(batSwitchOffIfBelow);
      buzzer.sound(SND_OVERCURRENT, true);
      if (switchOffAllowedUndervoltage)  batteryDriver.keepPowerOn(false);   
    } else if ((millis() >= switchOffTime) || (switchOffByOperator)) {
      DEBUGLN(F("SWITCHING OFF (idle timeout)"));           
      buzzer.sound(SND_OVERCURRENT, true);
      if ((switchOffAllowedIdle) || (switchOffByOperator)) batteryDriver.keepPowerOn(false);
    } else batteryDriver.keepPowerOn(true);           

    // battery voltage slope
    float w = 0.999;
    batteryVoltageSlope = w * batteryVoltageSlope + (1-w) * (batteryVoltage - batteryVoltageLast) * 60.0/5.0;   // 5s => 1min
    batteryVoltageLast = batteryVoltage;
  
    if (millis() >= nextSlopeTime){
      nextSlopeTime = millis() + 60000; // 1 minute
      badChargerContactState = false;
      if (chargerConnectedState){
        if (!chargingCompleted){
          if (chargingVoltBatteryVoltDiff < -3.0){
          //if (batteryVoltageSlope < 0){
            badChargerContactState = true;
            DEBUG(F("CHARGER BAD CONTACT chgV="));
            DEBUG(chargingVoltage);
            DEBUG(" batV=");
            DEBUG(batteryVoltage);
            DEBUG(" diffV=");
            DEBUG(chargingVoltBatteryVoltDiff);
            DEBUG(" slope(v/min)=");
            DEBUGLN(batteryVoltageSlope);
          }   
        }
      }
      if (abs(batteryVoltageSlope) < BAT_FULL_SLOPE){
        batteryVoltageSlopeLowCounter = min(10, batteryVoltageSlopeLowCounter + 1);
      } else {
        batteryVoltageSlopeLowCounter = 0; //max(0, batteryVoltageSlopeLowCounter - 1);
      }
    }

        if (millis() >= nextPrintTime){
            nextPrintTime = millis() + 60000;  // 1 minute                 
          
      //print();         
            /*DEBUG(F("charger conn="));
            DEBUG(chargerConnected());
            DEBUG(F(" chgEnabled="));
            DEBUG(chargingEnabled);
            DEBUG(F(" chgTime="));   
            DEBUG(timeMinutes);
            DEBUG(F(" charger: "));   
            DEBUG(chargingVoltage);
            DEBUG(F(" V  ")); 
            DEBUG(chargingCurrent); 
            DEBUG(F(" A "));       
            DEBUG(F(" bat: "));
            DEBUG(batteryVoltage);
            DEBUG(F(" V  ")); 
            DEBUG(F("switchOffAllowed=")); 
            DEBUG(switchOffAllowed);   
            DEBUGLN();      */                 
    } 
  }
 
  if (millis() > nextEnableTime){
    nextEnableTime = millis() + 5000;                 
  
    if (chargerConnectedState){       
        // charger in connected state
        if (chargingEnabled){
          //if ((timeMinutes > 180) || (chargingCurrent < batFullCurrent)) { 
          // https://github.com/Ardumower/Sunray/issues/32             
          if (chargingCompletedDelay > 5) {  // chargingCompleted check first after 6 * 5000ms = 30sec.
            chargingCompleted = ((chargingCurrent <= batFullCurrent) || (batteryVoltage >= batFullVoltage));
          }
          else {         
            chargingCompletedDelay++;
          }       
          if (chargingCompleted) {
            // stop charging
            nextEnableTime = millis() + 1000 * enableChargingTimeout;   // check charging current again in 30 minutes
            chargingCompleted = true;         
            enableCharging(false);
          }
        } else {
           //if (batteryVoltage < startChargingIfBelow) {
              // start charging
              enableCharging(true);
              chargingStartTime = millis();
          //}     
        } 
    }
    else {
      // reset to avoid direct undocking after docking 
      chargingCompleted       = false;
      chargingCompletedDelay  = 0;  // reset chargingCompleteted delay counter
    }

  }


}


First of all, you could enable the sd debug log vor the chargerconnected state. Then you can analyze what is happening.

@goosst I changed the config.h in master, at end of modsection you find DEBUG_BATTERY, set this true. Set SD_LOG also true, then you should have a 10 sec output with some bat data.
 
Zuletzt bearbeitet:
I haven't checked the master on github yet but, in the version I forked:
batteryVoltageSlope itself is nowhere used after the calculation. It just calculates batteryVoltageSlopeLowCounter which is nowhere used in the code (If I commented it out yesterday nothing complained in the code :)).

ok, I should have some time in the weekend to experiment (and try to upgrade to the master branch again).
(I've had not installed the sd-card ... ).

Is it not more efficient actually to work with issues on github?
 
yeah, it has nothing to do specific with suddenly be in docked state... but it´s used to calc the batt full state and cycle the charging if batt is considered full.

i just checked, actually you are totally right. it´s not used afterwards, looks like i missed some code during update XD

But still, this section should deliver some insight to the problem.
 
Zuletzt bearbeitet:
Hallo zusammen,
ich habe mal wieder ein Problem für welchen ich einen Tipp bräuchte woran es liegt. Über einen Hinweis würde ich mich sehr freuen.

Code:
In file included from /home/pi/Sunray/sunray/src/ublox/sfe_bus.cpp:54:
/home/pi/Sunray/sunray/src/ublox/sfe_bus.h:211:10: error: ‘void SparkFun_UBLOX_GNSS::SfePrint::print(const __FlashStringHelper*)’ cannot be overloaded with ‘void SparkFun_UBLOX_GNSS::SfePrint::print(const char*)’
  211 |     void print(const __FlashStringHelper *c)
      |          ^~~~~
/home/pi/Sunray/sunray/src/ublox/sfe_bus.h:206:10: note: previous declaration ‘void SparkFun_UBLOX_GNSS::SfePrint::print(const char*)’
  206 |     void print(const char *c)
      |          ^~~~~
/home/pi/Sunray/sunray/src/ublox/sfe_bus.h:236:10: error: ‘void SparkFun_UBLOX_GNSS::SfePrint::println(const __FlashStringHelper*)’ cannot be overloaded with ‘void SparkFun_UBLOX_GNSS::SfePrint::println(const char*)’
  236 |     void println(const __FlashStringHelper *c)
      |          ^~~~~~~
/home/pi/Sunray/sunray/src/ublox/sfe_bus.h:231:10: note: previous declaration ‘void SparkFun_UBLOX_GNSS::SfePrint::println(const char*)’
  231 |     void println(const char *c)
      |          ^~~~~~~
 
So I hooked up a raspberry pi with a powerbank to monitor the serial output of the arduino due. Very nice looking setup 🙃.
(Should probably just upgrade to a raspberry pi this winter without the esp32 etc. )

The event where the robot just reports "docked" out of the blue, I have not reproduced yet while recording data.
But I might have triggered something in the same line of issues:
  1. Ardumower was charging
  2. gave it a mow command, it slowly moved out of his house (i.e. charger is disconnected now).
  3. Mower seemed confused when getting out of his house (moving a few cm, stopping again, etc.). I've moved it by hand several meters further.
  4. Now mower reported a "docked" status.
  5. After rebooting the mower - through cassandra, not through the emergency button - it is working fine again.

Relevant recorded data:

the charging voltage just remains high / very slowly decades even when not connected to its charger. As a consequence, ardumower just reports docked.
(Disconnecting from charger must have happened where you see the small jump downwards in charging voltage.)
1726420790191.png


2024-09-15 18:08:15,726 root DEBUG charger conn=1 chgEnabled=1 chgTime=42 charger: 25.81 V 0.04 A bat: 26.43 V batslope: 0.01 V
2024-09-15 18:08:15,730 root DEBUG Op::eek:nChargerConnected
2024-09-15 18:08:15,732 root DEBUG setting to docking position


Since after rebooting, voltage looks fine again. I still seem to suspect a software rather than an electrical issue (or I have some sticky relais which gets opened after reboot ...).
 
Zuletzt bearbeitet:
Seems like the charger voltage reading gets stuck.
There is a low pass filter for that voltage but it should be fine.

You can print and log the output of this function: batteryDriver.getChargeVoltage();
Thats just reading directly from the pcb, if it gives you weird values I would suspect hardware.
 
Zuletzt bearbeitet:
Seems like the charger voltage reading gets stuck.
There is a low pass filter for that voltage but it should be fine.

You can print and log the output of this function: batteryDriver.getChargeVoltage();
Thats just reading directly from the pcb, if it gives you weird values I would suspect hardware.
indeed, I seemed to have put serial output of the unfiltered voltage on a poor location in the code ... , will be for next debugging session.

In case of interest, I had triggered something similar when it reported "docked" state during mowing / undocking.
1) mowing: filtered charger voltage = zero
2) docked / charging
3) starting to mow / undocking --> chargervoltage remained high entire time (despite not being in the station).
4) after a few minutes reports to be in docked state (and position jumps back). If there is still charging voltage being measured, I was surprised it still took several minutes to report again the docked state. (it did report charger conn=1 chgEnabled=1 all the time during the driving around.)
1726595679107.png

I suppose I'll need to inspect the Q4 mosfet / relay / Q1 on this bloody pcb. Seems dangerous if a full battery is connected to two naked pins ... .
Sorry for spamming on this software topic, most likely indeed just hardware.
For safety reasons, I could probably also come up with some forced opening of the relay when in a mowing state.
 
Zuletzt bearbeitet:
Oben