Skip to content

Commit 712ec27

Browse files
committed
Merge branch 'release/1.0a3-Azurit'
2 parents c41d6c4 + 27dc6ff commit 712ec27

File tree

84 files changed

+26874
-17090
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

84 files changed

+26874
-17090
lines changed

ardumower/mower.cpp

Lines changed: 35 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -289,16 +289,6 @@ void Mower::setup(){
289289
Console.println("SETUP");
290290
rc.initSerial(PFOD_BAUDRATE);
291291

292-
// http://sobisource.com/arduino-mega-pwm-pin-and-frequency-timer-control/
293-
// http://www.atmel.com/images/doc2549.pdf
294-
#ifdef __AVR__
295-
// NOTE: next line commented out so we can use default 450 Hz PWM freq (perimeter v2 otherwise uses the same freq band)
296-
// TCCR3B = (TCCR3B & 0xF8) | 0x02; // set PWM frequency 3.9 Khz (pin2,3,5)
297-
#endif
298-
299-
// i2c -- turn off internal pull-ups (and use external pull-ups)
300-
//digitalWrite(SDA, 0);
301-
//digitalWrite(SCL, 0);
302292

303293
// keep battery switched ON
304294
pinMode(pinBatterySwitch, OUTPUT);
@@ -394,6 +384,20 @@ void Mower::setup(){
394384
// other
395385
pinMode(pinVoltageMeasurement, INPUT);
396386

387+
// PWM frequency setup
388+
// For obstacle detection, motor torque should be detectable - torque can be computed by motor current.
389+
// To get consistent current values, PWM frequency should be 3.9 Khz
390+
// http://wiki.ardumower.de/index.php?title=Motor_driver
391+
// http://sobisource.com/arduino-mega-pwm-pin-and-frequency-timer-control/
392+
// http://www.atmel.com/images/doc2549.pdf
393+
#ifdef __AVR__
394+
TCCR3B = (TCCR3B & 0xF8) | 0x02; // set PWM frequency 3.9 Khz (pin2,3,5)
395+
#else
396+
analogWrite(pinMotorMowPWM, 0); // sets PWMEnabled=true in Arduino library
397+
pmc_enable_periph_clk(PWM_INTERFACE_ID);
398+
PWMC_ConfigureClocks(3900 * PWM_MAX_DUTY_CYCLE, 0, VARIANT_MCK); // 3.9 Khz
399+
#endif
400+
397401
// enable interrupts
398402
#ifdef __AVR__
399403
// R/C
@@ -449,24 +453,45 @@ void Mower::setup(){
449453
void checkMotorFault(){
450454
if (digitalRead(pinMotorLeftFault)==LOW){
451455
robot.addErrorCounter(ERR_MOTOR_LEFT);
456+
Console.println(F("Error: motor left fault"));
452457
robot.setNextState(STATE_ERROR, 0);
453458
//digitalWrite(pinMotorEnable, LOW);
454459
//digitalWrite(pinMotorEnable, HIGH);
455460
}
456461
if (digitalRead(pinMotorRightFault)==LOW){
457462
robot.addErrorCounter(ERR_MOTOR_RIGHT);
463+
Console.println(F("Error: motor right fault"));
458464
robot.setNextState(STATE_ERROR, 0);
459465
//digitalWrite(pinMotorEnable, LOW);
460466
//digitalWrite(pinMotorEnable, HIGH);
461467
}
462468
if (digitalRead(pinMotorMowFault)==LOW){
463469
robot.addErrorCounter(ERR_MOTOR_MOW);
470+
Console.println(F("Error: motor mow fault"));
464471
robot.setNextState(STATE_ERROR, 0);
465472
//digitalWrite(pinMotorMowEnable, LOW);
466473
//digitalWrite(pinMotorMowEnable, HIGH);
467474
}
468475
}
469476

477+
void Mower::resetMotorFault(){
478+
if (digitalRead(pinMotorLeftFault)==LOW){
479+
digitalWrite(pinMotorEnable, LOW);
480+
digitalWrite(pinMotorEnable, HIGH);
481+
Console.println(F("Reset motor left fault"));
482+
}
483+
if (digitalRead(pinMotorRightFault)==LOW){
484+
digitalWrite(pinMotorEnable, LOW);
485+
digitalWrite(pinMotorEnable, HIGH);
486+
Console.println(F("Reset motor right fault"));
487+
}
488+
if (digitalRead(pinMotorMowFault)==LOW){
489+
digitalWrite(pinMotorMowEnable, LOW);
490+
digitalWrite(pinMotorMowEnable, HIGH);
491+
Console.println(F("Reset motor mow fault"));
492+
}
493+
}
494+
470495

471496
int Mower::readSensor(char type){
472497
switch (type) {

ardumower/mower.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -40,6 +40,7 @@ class Mower : public Robot
4040
public:
4141
Mower();
4242
virtual void setup(void);
43+
virtual void resetMotorFault();
4344
virtual int readSensor(char type);
4445
virtual void setActuator(char type, int value);
4546
virtual void configureBluetooth(boolean quick);

ardumower/pfod.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -254,7 +254,9 @@ void RemoteControl::sendErrorMenu(boolean update){
254254
Bluetooth.print(F("|zz~GPS comm "));
255255
Bluetooth.print(robot->errorCounterMax[ERR_GPS_COMM]);
256256
Bluetooth.print(F("|zz~GPS data "));
257-
Bluetooth.print(robot->errorCounterMax[ERR_GPS_DATA]);
257+
Bluetooth.print(robot->errorCounterMax[ERR_GPS_DATA]);
258+
Bluetooth.print(F("|zz~EEPROM data "));
259+
Bluetooth.print(robot->errorCounterMax[ERR_EEPROM_DATA]);
258260
Bluetooth.println("}");
259261
}
260262

0 commit comments

Comments
 (0)