Alex's ardumower - My DIY ardumower modification

Because my garden isn't flat, was necessary start implementing improvements which I planned for new mower version 2018 (working name "Black pearl" :) ).
First is wheels change, because original plastic was good for flat garden, but on my garden sometimes wheels slip. So I bought new one. Price for both was 15Euro.
Also weight isn't so bad (0,75kg / one Wheel ).

WP_20170610_08_50_41_Rich.jpg


WP_20170610_08_53_33_Rich.jpg


Alex
Attachment: https://forum.ardumower.de/data/media/kunena/attachments/1183/WP_20170610_08_50_41_Rich.jpg/
 
Zuletzt bearbeitet von einem Moderator:
Regarding my post #12557 :
Perimeter tracking is working very good, but sometimes I had a perimeter timeout error. I found out, that mower is during tracking very often and long time tracking near to wire, but outside. So I changed code from :

if (perimeterInside) {
perimeterPID.w = -0.5;
}
else {
perimeterPID.w = 0.5;
}

to

if (perimeterInside) {
perimeterPID.w = -0.7;
}
else {
perimeterPID.w = 0.3;
}

now I'm tacking much often inside and error is gone.

Alex
 
Hi,
during my test I found one more problem. Currently with Timer :
When Timer is on and I have two defined times :
1 window - Monday - Friday 5:00 - 6:30
2 window - Monday - Friday 14:00 - 16:00

Problem is, that mower will start the operation and after minute will stop the operation and track into charging station. When it is in the station, after one minute will start operation again. I think it's problem in checkTimer :


Code:
// check timer
void Robot::checkTimer(){
  if (millis() < nextTimeTimer) return;
  nextTimeTimer = millis() + 60000;
  srand(time2minutes(datetime.time)); // initializes the pseudo-random number generator for c++ rand()
  randomSeed(time2minutes(datetime.time)); // initializes the pseudo-random number generator for arduino random()
  receiveGPSTime(); 
  boolean stopTimerTriggered = true;
  if (timerUse){    
    for (int i=0; i < MAX_TIMERS; i++){
      if (timer[i].active){
        if  ( (timer[i].daysOfWeek & (1 << datetime.date.dayOfWeek)) != 0) {
          int startmin = time2minutes(timer[i].startTime);
          int stopmin =  time2minutes(timer[i].stopTime);
          int currmin =  time2minutes(datetime.time);
          if ((currmin >= startmin) && (currmin < stopmin)){
            // start timer triggered
            stopTimerTriggered = false;
            if ((stateCurr == STATE_STATION) || (stateCurr == STATE_OFF)){
              Console.println(F("timer start triggered"));
              motorMowEnable = true;
              setNextState(STATE_FORWARD, 0);
            } 
          }           
        }
      if ((stopTimerTriggered) && (timer[i].active)){
      if (stateCurr == STATE_FORWARD){
        Console.println(F("timer stop triggered"));
        if (perimeterUse){
        setNextState(STATE_PERI_FIND, 0);
      }
        else setNextState(STATE_OFF,0);
      } 
    }
      }
    }
  }
}


I did a following code change :


Code:
// check timer
void Robot::checkTimer(){
  if (millis() < nextTimeTimer) return;
  nextTimeTimer = millis() + 60000;
  srand(time2minutes(datetime.time)); // initializes the pseudo-random number generator for c++ rand()
  randomSeed(time2minutes(datetime.time)); // initializes the pseudo-random number generator for arduino random()
  receiveGPSTime(); 
  
  boolean stopTimerTriggered = true;
  boolean oneTimerActive = false;
  
  if (timerUse){    
    for (int i=0; i < MAX_TIMERS; i++){
      if (timer[i].active){
        oneTimerActive = true;
        if  ( (timer[i].daysOfWeek & (1 << datetime.date.dayOfWeek)) != 0) {  
          int startmin = time2minutes(timer[i].startTime);
          int stopmin =  time2minutes(timer[i].stopTime);
          int currmin =  time2minutes(datetime.time);
          if ((currmin >= startmin) && (currmin < stopmin)){
            // start timer triggered
            stopTimerTriggered = false;
           } 
          }           
         }
        }
       if ((stopTimerTriggered) && (oneTimerActive)){
        if (stateCurr == STATE_FORWARD){
        Console.println(F("timer stop triggered"));
        if (perimeterUse){
        setNextState(STATE_PERI_FIND, 0);
        }
        else setNextState(STATE_OFF,0);
        } 
       }
       if ((!stopTimerTriggered) && (oneTimerActive)){
        if ((stateCurr == STATE_STATION) || (stateCurr == STATE_OFF)){
              Console.println(F("timer start triggered"));
              motorMowEnable = true;
              setNextState(STATE_FORWARD, 0);
        }
      }
   }
}


Now it's working as expected.


Now I'm in the situation, that mower is working in full automatic mode.
Tested functions : Timer and RTC, perimeter tracking, charging station (will send more informations soon), odometry, sonar, bumper.

Alex
 
One additional problem found with Timer / Charging station :

In robot.cpp :


Code:
case STATE_STATION:
      // waiting until auto-start by user or timer triggered
      if (batMonitor){
        if ((chgVoltage > 5.0) && (batVoltage > 8)){
          if (batVoltage < startChargingIfBelow && (millis()-stateStartTime>2000)){
            setNextState(STATE_STATION_CHARGING,0);
          } else checkTimer();  
        } else setNextState(STATE_OFF,0);
      }  else checkTimer();
      break;


problem is, that stat charging will start after 2seconds when you are in the station, but before timer is checked and mowing will start again if timer is active :

if (batVoltage < startChargingIfBelow && (millis()-stateStartTime>2000)){
setNextState(STATE_STATION_CHARGING,0);
} else checkTimer();

One possible solution is decrease value from 2000 to less or implement delay also on checktimer (you will ensure, that first is checked batVoltage and then timer) :


Code:
case STATE_STATION:
      // waiting until auto-start by user or timer triggered
      if (batMonitor){
        if ((chgVoltage > 5.0) && (batVoltage > 8)){
          if (batVoltage < startChargingIfBelow && (millis()-stateStartTime>2000)){
            setNextState(STATE_STATION_CHARGING,0);
          } else if (millis()-stateStartTime>2200)checkTimer();  
        } else setNextState(STATE_OFF,0);
      }  else checkTimer();
      break;


Then it's working very good and as expected.

Alex
 
Small code improvement, but result is the same :


Code:
case STATE_STATION:
      // waiting until auto-start by user or timer triggered
      if (millis()-stateStartTime>2000){
      if (batMonitor ){
        if ((chgVoltage > 5.0) && (batVoltage > 8)){
          if (batVoltage < startChargingIfBelow){
            setNextState(STATE_STATION_CHARGING,0);
          } else checkTimer();  
        } else setNextState(STATE_OFF,0);
      }  else checkTimer();
      }
      break;
 
After weeks and weeks SW code tweaking I have very good, fast and stable version for MEGA board. Let me share.
It's mixture of Azurit 106 and 107 + tweaks.
Main point :
-ONLY for MEGA boards
-smooth perimeter tweak with fixed Mag value (can be adjusted via Pfod). Also tracking speed can be adjusted
-new interrupt handling from Azurit 107
-MotorMowRPM - canceled - function for nothing - also complete code removed
-Timer improved and no problems with more Windows
- Changed procedure after mower arriving into charging station
- Only one way odometry - rest was canceled and code deleted
- DUE board canceled

After few days of testing in automatic mode I can say, that mower reaction is much better as before and mower is fully running in automatic mode (cutting,charging, cutting ....and according to time).
If you are interested, please download and test (but please, modify assignment of pins and interrupts).

..... and still improving for new 2018 SW+HW version Black Pearl.

Alex

MEGABOARDS-ALEX.zip

Attachment: https://forum.ardumower.de/data/media/kunena/attachments/1183/MEGABOARDS-ALEX.zip/
 
Zuletzt bearbeitet von einem Moderator:
Hi.
Also. And as you i remove all concerning the arduino i did not use but for me it's the MEGAB) .
Maybe it's good idea to make different version of code (DUE, MEGA PCB1.2 or 1.3) because the code is not very easy to understand if all is support in one code.
Why not AZURIT MEGA and AZURIT DUE but don't think Alexander like this!!
Good Week.
 
Sending pictures of the mower inside charging station (normaly with cover). This solution is working very stable for me. Planesets thickness is 0,2mm. Important is mounting of contacts from above.

WP_20170630_20_34_42_Rich.jpg


WP_20170630_20_34_51_Rich.jpg


And also sending Picture of improved bumpers :

WP_20170630_20_35_14_Rich.jpg


Why this bumpers :
- cheap, cheap ... cheap :) only brass profile for Modellers (in every shop), two microswitches, two springs, Two screws around which the Brass are rotated and base plate (all together aprox 7 Euro )
- Easy force regulation by spring change
- Both microswitches from upper side = no contact with grass
- Ready for future covering
- Both anvils in one line

Also found out a SW problem with rain sensor. I want place a rain sensor on the back side of the mower's cover which is still out of charging station, so mower will not leave charging station if it's raining, but this isn't treated in the software. SW modification I will send soon.....

Alex
Attachment: https://forum.ardumower.de/data/media/kunena/attachments/1183/WP_20170630_20_34_42_Rich.jpg/
 
Zuletzt bearbeitet von einem Moderator:
Next one SW change implemented :

When it's raining and mower is in station, mowing will not start till information from rain sensor is "no rain". Sure, rain sensor must be implemented and position of rain sensor on the mower's body is such, that rain sensor is still out of the station.

Code in robot.cpp :


Code:
case STATE_STATION: 
      // waiting until auto-start by user or timer triggered
      if (millis()-stateStartTime>2000){
      if (batMonitor ){
        if ((chgVoltage > 5.0) && (batVoltage > 8)){
          if (batVoltage < startChargingIfBelow){
            setNextState(STATE_STATION_CHARGING,0);
          } else if ((rainUse)&&(!rain)) checkTimer(); //no rain when ready in station
            else if (!rainUse) checkTimer(); //no rain sensor implemented
        } else setNextState(STATE_OFF,0);
      } else if ((rainUse)&&(!rain)) checkTimer(); //no rain when ready in station
        else if (!rainUse) checkTimer(); //no rain sensor implemented
      }
      break;


Alex
 
and bumper improvement. If bumper is touched and after reverse mode is still touched, mower is going to error, because bumper is stuck and mower will do reverse modes till will leave a loop and jump somewhere ......
robot.cpp :

add state :


Code:
char* stateNames[]={"OFF ", "RC  ", "FORW", "ROLL", "REV ", "CIRC", "ERR ", "PFND", "PTRK", "PROL", "PREV", "STAT", "CHARG", "STCHK",
  "STREV", "STROL", "STFOR", "MANU", "ROLW", "POUTFOR", "POUTREV", "POUTROLL", "BUMPSTUCK"};


modify :


Code:
// check bumpers
void Robot::checkBumpers(){
  if ((mowPatternCurr == MOW_BIDIR) && (millis() < stateStartTime + 4000)) return;

  if ((bumperLeft || bumperRight)) {  
       // immediate stop at bumping
       motorLeftRpmCurr = motorRightRpmCurr = 0 ;
       setMotorPWM( 0, 0, false );

    if (bumperLastTime){
      setNextState(STATE_BUMPER_STUCK, 0);
    }
    else if (bumperLeft) {
      reverseOrBidir(RIGHT); 
      bumperLastTime = true;
    }
    else{
      reverseOrBidir(LEFT); 
      bumperLastTime = true;
    }
  }   
  else bumperLastTime = false;

 }


into void Robot::setNextState(byte stateNew, byte dir) add :

Code:
if (stateNew == STATE_BUMPER_STUCK){  
    motorMowEnable = false;      
    motorLeftSpeedRpmSet = motorRightSpeedRpmSet = 0;   
  }


into main loop of robot.cpp :


Code:
case STATE_BUMPER_STUCK:  
      Console.println("error: bumper is stuck");  
      addErrorCounter(ERR_BUMPER_STUCK);  
      setNextState(STATE_ERROR,0);  
      break;  
    case STATE_STATION:


robot.h add err_bumper_stuck :


Code:
enum {
  ERR_MOTOR_LEFT,
  ERR_MOTOR_RIGHT,
  ERR_MOTOR_MOW,
  ERR_MOW_SENSE,
  ERR_IMU_COMM,
  ERR_IMU_TILT,
  ERR_RTC_COMM,
  ERR_RTC_DATA,
  ERR_PERIMETER_TIMEOUT,
  ERR_TRACKING,
  ERR_ODOMETRY_LEFT,
  ERR_ODOMETRY_RIGHT,
  ERR_BATTERY,
  ERR_CHARGER,
  ERR_GPS_COMM,
  ERR_GPS_DATA,
  ERR_ADC_CALIB,
  ERR_IMU_CALIB,
  ERR_EEPROM_DATA,
  ERR_STUCK,
  ERR_BUMPER_STUCK,
  // <---- add new error types here (NOTE: increase MAGIC to avoid corrupt EEPROM error data!)
  ERR_ENUM_COUNT,  
};


and state_bumper_stuck :


Code:
enum { 
  STATE_OFF,          // off
  STATE_REMOTE,       // model remote control (R/C)
  STATE_FORWARD,      // drive forward
  STATE_ROLL,         // drive roll right/left  
  STATE_REVERSE,      // drive reverse

  STATE_CIRCLE,       // drive circle  
  STATE_ERROR,        // error
  STATE_PERI_FIND,    // perimeter find 
  STATE_PERI_TRACK,   // perimeter track
  STATE_PERI_ROLL,    // perimeter roll
  STATE_PERI_REV,     // perimeter reverse
  STATE_STATION,       // in station
  STATE_STATION_CHARGING,       // in station charging
  STATE_STATION_CHECK, //checks if station is present
  STATE_STATION_REV,   // charge reverse
  STATE_STATION_ROLL,  // charge roll
  STATE_STATION_FORW,  // charge forward
  STATE_MANUAL,       // manual navigation  
  STATE_ROLL_WAIT,    // drive roll right/left
  STATE_PERI_OUT_FORW, // outside perimeter forward driving without checkPerimeterBoundary()
  STATE_PERI_OUT_REV,   // outside perimeter reverse driving without checkPerimeterBoundary()
  STATE_PERI_OUT_ROLL,   // outside perimeter rolling driving without checkPerimeterBoundary()
  STATE_BUMPER_STUCK, // Bumper is stuck
};



into pfod.cpp :
void RemoteControl::sendErrorMenu(boolean update){
add err_bumper_stuck:


Code:
serialPort->print(F("|zz~Bumper stuck "));
  serialPort->print(robot->errorCounterMax[ERR_BUMPER_STUCK]);  
  serialPort->print(F("|zz~EEPROM data "));
  serialPort->print(robot->errorCounterMax[ERR_EEPROM_DATA]);


And seriál monitor with new function :


Code:
buttonPressed
t     8 l3406 v0 OFF  odo    0    0 spd    0    0 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.6 chg  0.0  0.0 imu  0 adc 36 ALEX's Ardumower
t     0 l929 v0 FORW odo    0    0 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.6 chg  0.0  0.0 imu  0 adc  0 ALEX's Ardumower
t     0 l929 v0 FORW odo    0    0 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.6 chg  0.0  0.0 imu  0 adc104 ALEX's Ardumower
t     1 l2214 v0 FORW odo    0    0 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.5 chg  0.0  0.0 imu  0 adc116 ALEX's Ardumower
t     2 l2472 v0 FORW odo  120  117 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.5 chg  0.0  0.0 imu  0 adc115 ALEX's Ardumower
t     3 l2448 v0 FORW odo  245  242 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.5 chg  0.0  0.0 imu  0 adc117 ALEX's Ardumower
t     4 l2457 v0 FORW odo  372  370 spd   27   27 sen    0    0    0 bum    0    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc116 ALEX's Ardumower
t     0 l2447 v0 REV  odo  383  381 spd  -21  -21 sen    0    0    0 bum    1    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc  1 ALEX's Ardumower
t     0 l2447 v0 REV  odo  386  385 spd  -21  -21 sen    0    0    0 bum   10    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc106 ALEX's Ardumower
t     1 l2451 v0 REV  odo  386  385 spd  -21  -21 sen    0    0    0 bum   20    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc112 ALEX's Ardumower
t     2 l2682 v0 REV  odo  310  309 spd  -21  -21 sen    0    0    0 bum   30    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc116 ALEX's Ardumower
t     0 l2670 v0 ROLL odo  280  286 spd   21  -21 sen    0    0    0 bum   32    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc 31 ALEX's Ardumower
t     0 l2670 v0 BUMPSTUCK odo  273  277 spd    0    0 sen    0    0    0 bum   33    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc  1 ALEX's Ardumower
error: bumper is stuck
t     0 l2670 v0 ERR  odo  274  278 spd    0    0 sen    0    0    0 bum   33    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc  0 ALEX's Ardumower
t     0 l2670 v0 ERR  odo  275  279 spd    0    0 sen    0    0    0 bum   36    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc 23 ALEX's Ardumower
t     1 l1134 v0 ERR  odo  275  279 spd    0    0 sen    0    0    0 bum   46    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc116 ALEX's Ardumower
t     2 l3548 v0 ERR  odo  275  279 spd    0    0 sen    0    0    0 bum   52    0 dro    0    0 son   0 yaw   0 pit   0 rol   0 per   2 bat 24.4 chg  0.0  0.0 imu  0 adc116 ALEX's Ardumower
t     3 l3542 v0 ERR



Alex
 
Hi,
I am creating my own mower using an Arduino Mega and writing my own code. So far everything was working but for the perimeter wire sensor I couldn't code it and decided instead to use the ARDUMOWER code which requires the use of the ADCMan.h library. Now all the Analogread() functions I had in my own code dont work anymore due to the ADCMan library.

I need to change these into ADCMan functions but cannot get it to work. I have a rain sensor on pin A1 and a voltage sensor on pin A3.
Could you please help me with lines of code to read the vaules at A1 and A3 using the ADCMan functions?

Thanks
Phil.
 
Hi Phil,
Not sure if I'm right person to help you. But maybe you can try share your code.
But regarding rain sensor - you don't need a analog signal, because there is only on/off signal.
Alex
 
Oben