Skip to content

Commit

Permalink
Merge branch 'release/1.0a3-Azurit'
Browse files Browse the repository at this point in the history
  • Loading branch information
autega committed May 25, 2015
2 parents c41d6c4 + 27dc6ff commit 712ec27
Show file tree
Hide file tree
Showing 84 changed files with 26,874 additions and 17,090 deletions.
45 changes: 35 additions & 10 deletions ardumower/mower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -289,16 +289,6 @@ void Mower::setup(){
Console.println("SETUP");
rc.initSerial(PFOD_BAUDRATE);

// http://sobisource.com/arduino-mega-pwm-pin-and-frequency-timer-control/
// http://www.atmel.com/images/doc2549.pdf
#ifdef __AVR__
// NOTE: next line commented out so we can use default 450 Hz PWM freq (perimeter v2 otherwise uses the same freq band)
// TCCR3B = (TCCR3B & 0xF8) | 0x02; // set PWM frequency 3.9 Khz (pin2,3,5)
#endif

// i2c -- turn off internal pull-ups (and use external pull-ups)
//digitalWrite(SDA, 0);
//digitalWrite(SCL, 0);

// keep battery switched ON
pinMode(pinBatterySwitch, OUTPUT);
Expand Down Expand Up @@ -394,6 +384,20 @@ void Mower::setup(){
// other
pinMode(pinVoltageMeasurement, INPUT);

// PWM frequency setup
// For obstacle detection, motor torque should be detectable - torque can be computed by motor current.
// To get consistent current values, PWM frequency should be 3.9 Khz
// http://wiki.ardumower.de/index.php?title=Motor_driver
// http://sobisource.com/arduino-mega-pwm-pin-and-frequency-timer-control/
// http://www.atmel.com/images/doc2549.pdf
#ifdef __AVR__
TCCR3B = (TCCR3B & 0xF8) | 0x02; // set PWM frequency 3.9 Khz (pin2,3,5)
#else
analogWrite(pinMotorMowPWM, 0); // sets PWMEnabled=true in Arduino library
pmc_enable_periph_clk(PWM_INTERFACE_ID);
PWMC_ConfigureClocks(3900 * PWM_MAX_DUTY_CYCLE, 0, VARIANT_MCK); // 3.9 Khz
#endif

// enable interrupts
#ifdef __AVR__
// R/C
Expand Down Expand Up @@ -449,24 +453,45 @@ void Mower::setup(){
void checkMotorFault(){
if (digitalRead(pinMotorLeftFault)==LOW){
robot.addErrorCounter(ERR_MOTOR_LEFT);
Console.println(F("Error: motor left fault"));
robot.setNextState(STATE_ERROR, 0);
//digitalWrite(pinMotorEnable, LOW);
//digitalWrite(pinMotorEnable, HIGH);
}
if (digitalRead(pinMotorRightFault)==LOW){
robot.addErrorCounter(ERR_MOTOR_RIGHT);
Console.println(F("Error: motor right fault"));
robot.setNextState(STATE_ERROR, 0);
//digitalWrite(pinMotorEnable, LOW);
//digitalWrite(pinMotorEnable, HIGH);
}
if (digitalRead(pinMotorMowFault)==LOW){
robot.addErrorCounter(ERR_MOTOR_MOW);
Console.println(F("Error: motor mow fault"));
robot.setNextState(STATE_ERROR, 0);
//digitalWrite(pinMotorMowEnable, LOW);
//digitalWrite(pinMotorMowEnable, HIGH);
}
}

void Mower::resetMotorFault(){
if (digitalRead(pinMotorLeftFault)==LOW){
digitalWrite(pinMotorEnable, LOW);
digitalWrite(pinMotorEnable, HIGH);
Console.println(F("Reset motor left fault"));
}
if (digitalRead(pinMotorRightFault)==LOW){
digitalWrite(pinMotorEnable, LOW);
digitalWrite(pinMotorEnable, HIGH);
Console.println(F("Reset motor right fault"));
}
if (digitalRead(pinMotorMowFault)==LOW){
digitalWrite(pinMotorMowEnable, LOW);
digitalWrite(pinMotorMowEnable, HIGH);
Console.println(F("Reset motor mow fault"));
}
}


int Mower::readSensor(char type){
switch (type) {
Expand Down
1 change: 1 addition & 0 deletions ardumower/mower.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,7 @@ class Mower : public Robot
public:
Mower();
virtual void setup(void);
virtual void resetMotorFault();
virtual int readSensor(char type);
virtual void setActuator(char type, int value);
virtual void configureBluetooth(boolean quick);
Expand Down
4 changes: 3 additions & 1 deletion ardumower/pfod.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,7 +254,9 @@ void RemoteControl::sendErrorMenu(boolean update){
Bluetooth.print(F("|zz~GPS comm "));
Bluetooth.print(robot->errorCounterMax[ERR_GPS_COMM]);
Bluetooth.print(F("|zz~GPS data "));
Bluetooth.print(robot->errorCounterMax[ERR_GPS_DATA]);
Bluetooth.print(robot->errorCounterMax[ERR_GPS_DATA]);
Bluetooth.print(F("|zz~EEPROM data "));
Bluetooth.print(robot->errorCounterMax[ERR_EEPROM_DATA]);
Bluetooth.println("}");
}

Expand Down
Loading

0 comments on commit 712ec27

Please sign in to comment.