Skip to content

Commit 05b02fe

Browse files
committed
Merge branch 'release/1.0a2-Azurit'
2 parents 2190feb + 54e8d13 commit 05b02fe

File tree

3 files changed

+12
-9
lines changed

3 files changed

+12
-9
lines changed

ardumower/mower.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -154,7 +154,7 @@ Mower::Mower(){
154154
// ------ mower motor -------------------------------
155155
motorMowAccel = 0.1; // motor mower acceleration (warning: do not set too high)
156156
motorMowSpeedMaxPwm = 255; // motor mower max PWM
157-
motorMowPowerMax = 50.0; // motor mower max power (Watt)
157+
motorMowPowerMax = 75.0; // motor mower max power (Watt)
158158
motorMowModulate = 0; // motor mower cutter modulation?
159159
motorMowRPMSet = 3300; // motor mower RPM (only for cutter modulation)
160160
motorMowSenseScale = 15.3; // motor mower sense scale (mA=(ADC-zero)/scale)

ardumower/perimeter.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -50,7 +50,7 @@
5050

5151

5252
Perimeter::Perimeter(){
53-
useDifferentialPerimeterSignal = false;
53+
useDifferentialPerimeterSignal = true;
5454
swapCoilPolarity = false;
5555
timedOutIfBelowSmag = 300;
5656
timeOutSecIfNotInside = 8;
@@ -248,4 +248,4 @@ int16_t Perimeter::corrFilter(int8_t *H, int8_t subsample, int16_t M, int8_t *ip
248248

249249

250250

251-
251+

ardumower/robot.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1398,8 +1398,11 @@ void Robot::readSensors(){
13981398
}
13991399
}
14001400
if (perimeter.signalTimedOut(0)) {
1401-
if ( (stateCurr != STATE_OFF) && (stateCurr != STATE_MANUAL) && (stateCurr != STATE_STATION) && (stateCurr != STATE_STATION_CHARGING) && (stateCurr != STATE_REMOTE)) {
1402-
Console.println(F("Error: perimeter too far away"));
1401+
if ( (stateCurr != STATE_OFF) && (stateCurr != STATE_MANUAL) && (stateCurr != STATE_STATION)
1402+
&& (stateCurr != STATE_STATION_CHARGING) && (stateCurr != STATE_STATION_CHECK)
1403+
&& (stateCurr != STATE_STATION_REV) && (stateCurr != STATE_STATION_ROLL)
1404+
&& (stateCurr != STATE_STATION_FORW) && (stateCurr != STATE_REMOTE)) {
1405+
Console.println("Error: perimeter too far away");
14031406
addErrorCounter(ERR_PERIMETER_TIMEOUT);
14041407
setNextState(STATE_ERROR,0);
14051408
}
@@ -1584,18 +1587,18 @@ void Robot::setNextState(byte stateNew, byte dir){
15841587
rollDir = dir;
15851588
if (stateNew == STATE_STATION_REV){
15861589
motorLeftSpeedRpmSet = motorRightSpeedRpmSet = -motorSpeedMaxRpm;
1587-
stateEndTime = millis() + stationRevTime;
1590+
stateEndTime = millis() + stationRevTime + motorZeroSettleTime;
15881591
} else if (stateNew == STATE_STATION_ROLL){
15891592
motorLeftSpeedRpmSet = motorSpeedMaxRpm;
15901593
motorRightSpeedRpmSet = -motorLeftSpeedRpmSet;
1591-
stateEndTime = millis() + stationRollTime;
1594+
stateEndTime = millis() + stationRollTime + motorZeroSettleTime;
15921595
} else if (stateNew == STATE_STATION_FORW){
15931596
motorLeftSpeedRpmSet = motorRightSpeedRpmSet = motorSpeedMaxRpm;
15941597
motorMowEnable = true;
1595-
stateEndTime = millis() + stationForwTime;
1598+
stateEndTime = millis() + stationForwTime + motorZeroSettleTime;
15961599
} else if (stateNew == STATE_STATION_CHECK){
15971600
motorLeftSpeedRpmSet = motorRightSpeedRpmSet = -motorSpeedMaxRpm/2;
1598-
stateEndTime = millis() + stationCheckTime;
1601+
stateEndTime = millis() + stationCheckTime + motorZeroSettleTime;
15991602

16001603
} else if (stateNew == STATE_PERI_ROLL) {
16011604
stateEndTime = millis() + perimeterTrackRollTime;

0 commit comments

Comments
 (0)