Skip to content

Commit

Permalink
Fix for single coil setup for mower.
Browse files Browse the repository at this point in the history
  • Loading branch information
PalmOla authored and sm6yvr committed Jul 14, 2017
1 parent f361b22 commit 7bd5f48
Show file tree
Hide file tree
Showing 6 changed files with 19 additions and 21 deletions.
2 changes: 1 addition & 1 deletion Liam/BWFSensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ void BWFSENSOR::clearSignal() {


bool BWFSENSOR::isInside() {
return (signal_status == INSIDE);
return (signal_status == INSIDE);
}

bool BWFSENSOR::isOutside() {
Expand Down
4 changes: 2 additions & 2 deletions Liam/Battery.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,8 @@ word BATTERY::readBatteryAndCalcValue(){
unsigned long newReading = analogRead(batSocpin);
newReading = newReading * 488 * VOLTDIVATOR;
newReading /= 10000;
return newReading;
//return word(newReading);
//return newReading;
return word(newReading);
}

bool BATTERY::isBeingCharged() {
Expand Down
8 changes: 4 additions & 4 deletions Liam/Battery.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,10 @@ Placed under the GNU license
#define LIION 2

//All voltage value need to be x100 to avoid decimals (12.54V = 1254)
#define LIIONFULL 1300
#define LIIONEMPTY 1040
#define NIMHFULL 1450
#define NIMHEMPTY 1150
#define LIIONFULL 1256
#define LIIONEMPTY 1040
#define NIMHFULL 1450
#define NIMHEMPTY 1150
#define LEADACIDFULL 1330
#define LEADACIDEMPTY 1200

Expand Down
20 changes: 9 additions & 11 deletions Liam/Controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,15 @@ int CONTROLLER::turnToReleaseRight(int angle) {
sensor->select(0);

if (sensor->isInside()) {
sensor->select(1);
if (sensor->isInside())
return 0; // OK
// Only check sensor one if more than 1 sensor defined.
if(NUMBER_OF_SENSORS>1)
{
sensor->select(1);
if (sensor->isInside())
return 0; // OK
}
else
return 0; // OK
}

if (wheelsAreOverloaded())
Expand Down Expand Up @@ -292,18 +298,10 @@ boolean CONTROLLER::hasBumped() {
}

boolean CONTROLLER::hasTilted() {
Serial.println("");
Serial.println("NU är tiltvärdet :");
Serial.println(compass->getTiltAngle(), DEC);
Serial.println(compass->getTiltAngle() > TILTANGLE);
return (compass->getTiltAngle() > TILTANGLE);
}

boolean CONTROLLER::hasFlipped() {
Serial.println("");
Serial.println("NU är Flippvärdet :");
Serial.println(compass->getTiltAngle(), DEC);
Serial.println(compass->getTiltAngle() > FLIPANGLE);
return (compass->getTiltAngle() > FLIPANGLE);
}

Expand Down
4 changes: 2 additions & 2 deletions Liam/Definition.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,10 +65,10 @@ const int MY_CUTTERMOTOR = 1;
const int MY_BATTERY = 2;

/* Number of BWF sensors can be 1-4 depending on shield */
const int NUMBER_OF_SENSORS = 2;
const int NUMBER_OF_SENSORS = 1;

/* BWF transmitter signals */
#define INSIDE_BWF 85
#define INSIDE_BWF 86
#define OUTSIDE_BWF 5

/* If you have a bumper connected to pin8, set it to true. Remember to cut the brake connection on your motor shield */
Expand Down
2 changes: 1 addition & 1 deletion Liam/Liam.ino
Original file line number Diff line number Diff line change
Expand Up @@ -269,7 +269,7 @@ void loop() {
state = DOCKING;
break;
}

// Tries to turn, but if timeout then reverse and try again
if ((err = Mower.turnToReleaseRight(30) > 0)) {
Mower.runBackward(FULLSPEED);
Expand Down

0 comments on commit 7bd5f48

Please sign in to comment.