Skip to content

Commit

Permalink
Convert mower control to bldc with esc
Browse files Browse the repository at this point in the history
  • Loading branch information
jordojordo committed Jan 28, 2024
1 parent 7a86ee1 commit c2108e9
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 27 deletions.
2 changes: 2 additions & 0 deletions lawndon/drive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@ void Drive::setup() {
delay(1);

// Calibrate ESCs ( Needed for initial setup )
// Console.println(F("Calibrating left ESC"));
// calibrateEsc(leftEsc);
// Console.println(F("Calibrating right ESC"));
// calibrateEsc(rightEsc);

// Arm ESCs
Expand Down
4 changes: 2 additions & 2 deletions lawndon/drive.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@ extern Servo leftEsc;
extern Servo rightEsc;

// pin defs
#define ESC_LEFT_PWM 3
#define ESC_LEFT_POWER 4
#define ESC_LEFT_PWM 4
#define ESC_LEFT_POWER 3

#define ESC_RIGHT_PWM 11
#define ESC_RIGHT_POWER 10
Expand Down
35 changes: 15 additions & 20 deletions lawndon/motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,41 +2,36 @@
#include "controller.h"
#include <Arduino.h>
#include <IBusBM.h>
#include <Servo.h>

Motor motor;
Servo mowerEsc;

Motor::Motor() {}

void Motor::setup() {
Console.println(F("Initializing motor config"));

setupTimer4();
pinMode(motorEnaR, OUTPUT);
pinMode(motorEnaL, OUTPUT);
pinMode(motorPwmR, OUTPUT);
pinMode(motorPwmL, OUTPUT);
// Attach Mower ESC
Console.println(F("Attaching mower ESC"));
mowerEsc.attach(ESC_MOWER_PWM, 1000, 2000);
delay(1);

digitalWrite(motorEnaR, HIGH);
digitalWrite(motorEnaL, HIGH);
analogWrite(motorPwmR, LOW);
analogWrite(motorPwmL, LOW);
// Arm Mower ESC
Console.println(F("Arming mower ESC"));
mowerEsc.writeMicroseconds(1000);

// Set mower ESC pins
pinMode(ESC_MOWER_PWM, OUTPUT);
pinMode(ESC_MOWER_POWER, OUTPUT);

Console.println(F("Motor setup complete"));
}

void Motor::loop() {
int swdOut = map(controller.control_CH9_swd, 0, 1, 0, 255);

if (controller.control_CH9_swd == 1) {
analogWrite(motorPwmR, swdOut);
mowerEsc.writeMicroseconds(2000);
} else {
analogWrite(motorPwmR, swdOut);
mowerEsc.writeMicroseconds(1000);
}
}

// Adjusts Timer4 for a frequency of 1kHz
// [optional]: depends on the mower motor requirements
void Motor::setupTimer4() {
TCCR4B = TCCR4B & 0b11111000 | 0x01; // Change prescaler
ICR4 = 32000; // Adjust the TOP value for 1kHz at 16MHz clock speed
}
7 changes: 2 additions & 5 deletions lawndon/motor.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,18 +5,15 @@
#include <Arduino.h>

// Mower Motor pins
#define motorEnaR 22
#define motorEnaL 23
#define motorPwmR 6
#define motorPwmL 7
#define ESC_MOWER_POWER 6
#define ESC_MOWER_PWM 7

class Motor {
public:
Motor();

virtual void setup();
virtual void loop();
virtual void setupTimer4();
};

extern Motor motor;
Expand Down

0 comments on commit c2108e9

Please sign in to comment.