Hallo Zusammen,
heute möchte ich mit euch die neuesten Verbesserungen an der Firmware von meinem Schaf teilen.
Viele von uns haben Probleme mit der Geradeausfahrt des Mowers und dem Sonar.
Das kommt meiner Meinung nach von den Odometrie-Interrupts, sprich zuviele, insbesondere wenn die Sonar viel CPU-Zeit durch die pulsIn-Funktion beanspruchen.
Um die Odometrie-Interrupts zu minimieren habe ist mein Schaf schon längere Zeit mit der "OneWay-Odometrie" unterwegs.
Das bring aber was die Interrupts angeht nichts oder nicht viel, solange alle Hallsensoren mit dem Mega verbunden sind, werden die Interrupte noch immer ausgelöst.
Eine kleine Änderung in der mower.cpp schaft Abhilfe (siehe da, das Schaf fährt gerade):
Code:
...
// enable interrupts
#ifdef __AVR__
// R/C
PCICR |= (1<<PCIE0);
PCMSK0 |= (1<<PCINT4);
PCMSK0 |= (1<<PCINT5);
PCMSK0 |= (1<<PCINT6);
PCMSK0 |= (1<<PCINT1);
// odometry
PCICR |= (1<<PCIE2);
PCMSK2 |= (1<<PCINT20);
//PCMSK2 |= (1<<PCINT21); //do not enable this interrupt for OneWayOdometry
PCMSK2 |= (1<<PCINT22);
//PCMSK2 |= (1<<PCINT23); //do not enable this interrupt for OneWayOdometry
...
Für die Sonar gibts auch eine Verbesserung, da die CPU jetzt nicht mehr so doll mit Odometrie-Interrupts belastet ist:
-> Sonar über Interrupts auswerten... am einfachsten mit einer schon existierenden Librarry:
NewPing von Tim Eckel
Und plötzlich wird Sonar-auswertung bis zu 4m möglich und gut:
Dumm nur, das die Librarry den Timer2 vom Mega verwendet.... kann man aber in der NewPing.h einfach ausschalten:
Code:
...
#define TIMER_ENABLED false // Set to "false" to disable the timer ISR (if getting "__vector_7" compile errors set this to false). Default=true
...
Die zwei Dateien (NewPing.h und NewPing.cpp) in den Ardumower Ordner einfügen und
noch ein paar Zeilen Code ändern:
mower.cpp
Code:
....
#include "config.h"
#ifdef USE_MOWER
#include "NewPing.h"
#include <Arduino.h>
#include "mower.h"
#include "due.h"
....
Code:
...
boolean motorMowRpmState = digitalRead(pinMotorMowRpm);
robot.setOdometryState(timeMicros, odometryLeftState, odometryRightState, odometryLeftState2, odometryRightState2);
robot.setMotorMowRPMState(motorMowRpmState);
}
// mower motor speed sensor interrupt
//void rpm_interrupt(){
//}
NewPing NewSonarLeft(pinSonarLeftTrigger, pinSonarLeftEcho, 500);
NewPing NewSonarRight(pinSonarRightTrigger, pinSonarRightEcho, 500);
NewPing NewSonarCenter(pinSonarCenterTrigger, pinSonarCenterEcho, 500);
...
Code:
...
// sonar---------------------------------------------------------------------------------------------------
//case SEN_SONAR_CENTER: return(readURM37(pinSonarCenterTrigger, pinSonarCenterEcho)); break;
// case SEN_SONAR_CENTER: return(readHCSR04(pinSonarCenterTrigger, pinSonarCenterEcho)); break;
// case SEN_SONAR_LEFT: return(readHCSR04(pinSonarLeftTrigger, pinSonarLeftEcho)); break;
// case SEN_SONAR_RIGHT: return(readHCSR04(pinSonarRightTrigger, pinSonarRightEcho)); break;
case SEN_SONAR_CENTER: return(NewSonarCenter.ping_cm()); break;
case SEN_SONAR_LEFT: return(NewSonarLeft.ping_cm()); break;
case SEN_SONAR_RIGHT: return(NewSonarRight.ping_cm()); break;
// case SEN_LAWN_FRONT: return(measureLawnCapacity(pinLawnFrontSend, pinLawnFrontRecv)); break;
//case SEN_LAWN_BACK: return(measureLawnCapacity(pinLawnBackSend, pinLawnBackRecv)); break;
...
robot.cpp
Code:
...
if ((sonarUse) && (millis() >= nextTimeSonar)){
static char senSonarTurn = SEN_SONAR_RIGHT;
nextTimeSonar = millis() + 80;
switch(senSonarTurn) {
case SEN_SONAR_RIGHT:
if (sonarRightUse) sonarDistRight = readSensor(SEN_SONAR_RIGHT);
senSonarTurn = SEN_SONAR_LEFT;
break;
case SEN_SONAR_LEFT:
if (sonarLeftUse) sonarDistLeft = readSensor(SEN_SONAR_LEFT);
senSonarTurn = SEN_SONAR_CENTER;
break;
case SEN_SONAR_CENTER:
if (sonarCenterUse) sonarDistCenter = readSensor(SEN_SONAR_CENTER);
senSonarTurn = SEN_SONAR_RIGHT;
break;
default:
senSonarTurn = SEN_SONAR_RIGHT;
break;
}
/*
if (sonarRightUse) sonarDistRight = readSensor(SEN_SONAR_RIGHT);
if (sonarLeftUse) sonarDistLeft = readSensor(SEN_SONAR_LEFT);
if (sonarCenterUse) sonarDistCenter = readSensor(SEN_SONAR_CENTER);
*/
...
pfod.cpp
Code:
...
void RemoteControl::sendSonarMenu(boolean update){
if (update) Bluetooth.print("{:"); else Bluetooth.print(F("{.Sonar`1000"));
Bluetooth.print(F("|d00~Use "));
sendYesNo(robot->sonarUse);
Bluetooth.print(F("|d04~Use left "));
sendYesNo(robot->sonarLeftUse);
Bluetooth.print(F("|d05~Use center "));
sendYesNo(robot->sonarCenterUse);
Bluetooth.print(F("|d06~Use right "));
sendYesNo(robot->sonarRightUse);
Bluetooth.print(F("|d01~Counter "));
Bluetooth.print(robot->sonarDistCounter);
Bluetooth.println(F("|d02~Value l, c, r"));
Bluetooth.print(robot->sonarDistLeft);
Bluetooth.print(", ");
Bluetooth.print(robot->sonarDistCenter);
Bluetooth.print(", ");
Bluetooth.print(robot->sonarDistRight);
sendSlider("d03", F("Trigger below"), robot->sonarTriggerBelow, "", 1, 80);
Bluetooth.println("}");
...
und schon müsste das funktionieren...
ich hoffe nichts vergessen zu haben...
Ich bin jetzt auch wieder auf 38kHz Samplerate im ADCMAN. Die paar kleinen Änderungen haben für mein schaf viel gebracht....
Gruess
Chris
Attachment:
https://forum.ardumower.de/data/media/kunena/attachments/2380/NewPing.jpg/