-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Update reverse/turning control - add release workflow
- Loading branch information
1 parent
0fbaa54
commit 6df8681
Showing
11 changed files
with
239 additions
and
204 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,44 @@ | ||
name: Compile Lawndon Lite | ||
|
||
on: | ||
workflow_dispatch: | ||
release: | ||
types: [released] | ||
|
||
jobs: | ||
compile-sketch: | ||
runs-on: ubuntu-latest | ||
permissions: | ||
contents: write | ||
|
||
steps: | ||
- name: Checkout repository | ||
uses: actions/checkout@v4 | ||
|
||
- name: Install Arduino cli | ||
uses: arduino/setup-arduino-cli@v1 | ||
|
||
- name: Install libraries | ||
run: | | ||
arduino-cli lib install --git-url https://github.com/bmellink/IBusBM.git#1.1.5 | ||
arduino-cli lib install --git-url https://github.com/arduino-libraries/Servo.git#1.2.1 | ||
- name: Compile Lawndon | ||
uses: arduino/compile-sketches@v1 | ||
with: | ||
fqbn: "arduino:avr:mega" | ||
libraries: | | ||
- name: IBusBM | ||
- name: Servo | ||
sketch-paths: | | ||
- ./lawndon | ||
enable-warnings-report: true | ||
verbose: false | ||
cli-compile-flags: | | ||
- --export-binaries | ||
- name: Release | ||
uses: softprops/action-gh-release@v1 | ||
if: startsWith(github.ref, 'refs/tags/') | ||
with: | ||
files: ./lawndon/build |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,2 +1,3 @@ | ||
#include "drive.h" | ||
#include "controller.h" | ||
#include "motor.h" |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,42 @@ | ||
#include "controller.h" | ||
#include <Arduino.h> | ||
|
||
IBusBM ibus; | ||
Controller controller; | ||
|
||
Controller::Controller() {} | ||
|
||
// Reads the supplied channel from Serial1 (ControllerPort) and | ||
// returns either the supplied default value or a mapped value between limits | ||
int Controller::readChannel(byte channelInput, int minLimit, int maxLimit, | ||
int defaultValue) { | ||
uint16_t ch = ibus.readChannel(channelInput); | ||
|
||
if (ch < 100) { | ||
return defaultValue; | ||
} | ||
|
||
return map(ch, 1000, 2000, minLimit, maxLimit); | ||
}; | ||
|
||
void Controller::setup() { | ||
Console.println(F("Sending Controller Config")); | ||
ControllerPort.begin(CONTROLLER_BAUDRATE); | ||
ibus.begin(ControllerPort); | ||
} | ||
|
||
void Controller::loop() { | ||
// Right joystick | ||
control_CH1_roll = readChannel(0, 1000, 2000, 1500); // roll | L -> R | ||
control_CH2_pitch = readChannel(1, 1000, 2000, 1500); // pitch | Up -> Down | ||
|
||
// Unused | ||
// control_CH3_throttle = readChannel(2, 1000, 2000, 1500); // throttle | Up -> Down | ||
// control_CH4_yaw = readChannel(3, 1000, 2000, 1500); // yaw | L -> R | ||
// control_CH6_swa = readChannel(6, 0, 1, 0); | ||
// control_CH7_swb = readChannel(7, 0, 1, 0); | ||
// control_CH8_swc = readChannel(8, 0, 2, 0); | ||
|
||
// Mower motor switch | ||
control_CH9_swd = readChannel(9, 0, 1, 0); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,43 @@ | ||
#ifndef CONTROLLER_H | ||
#define CONTROLLER_H | ||
|
||
#include <Arduino.h> | ||
#include <IBusBM.h> | ||
|
||
// baudrates | ||
#define CONSOLE_BAUDRATE 19200 | ||
#define CONTROLLER_BAUDRATE 115200 | ||
|
||
// serial ports | ||
#define Console Serial | ||
#define ControllerPort Serial1 | ||
|
||
class Controller { | ||
public: | ||
// Right joystick | ||
int control_CH1_roll = 0; // roll | L -> R | ||
int control_CH2_pitch = 0; // pitch | Up -> Down | ||
|
||
// Unused | ||
// int control_CH3_throttle = 0; // throttle | Up -> Down | ||
// int control_CH4_yaw = 0; // yaw | L -> R | ||
// int control_CH6_swa = 0; | ||
// int control_CH7_swb = 0; | ||
// int control_CH8_swc = 0; | ||
|
||
// Motor mower switch | ||
int control_CH9_swd = 0; | ||
|
||
Controller(); | ||
|
||
virtual void setup(); | ||
virtual void loop(); | ||
|
||
virtual int readChannel(byte channelInput, int minLimit, int maxLimit, | ||
int defaultValue); | ||
}; | ||
|
||
extern IBusBM ibus; | ||
extern Controller controller; | ||
|
||
#endif // CONTROLLER_H |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,68 +1,97 @@ | ||
#include "drive.h" | ||
#include "flysky.h" | ||
#include "controller.h" | ||
#include <Arduino.h> | ||
#include <Servo.h> | ||
|
||
Servo leftEsc; | ||
Servo rightEsc; | ||
Drive drive; | ||
|
||
Drive::Drive() {}; | ||
|
||
void Drive::setup() { | ||
Serial.begin(CONSOLE_BAUDRATE); | ||
Serial.println(F("SETUP")); | ||
Console.begin(CONSOLE_BAUDRATE); | ||
Console.println(F("SETUP")); | ||
|
||
leftEsc.attach(pinDriveLeftPwm, 1000, 2000); | ||
rightEsc.attach(pinDriveRightPwm, 1000, 2000); | ||
// Attach ESCs | ||
leftEsc.attach(ESC_LEFT_PWM, 1000, 2000); | ||
rightEsc.attach(ESC_RIGHT_PWM, 1000, 2000); | ||
delay(1); | ||
|
||
// Arm escs | ||
leftEsc.write(40); | ||
rightEsc.write(40); | ||
// Calibrate ESCs | ||
calibrateEsc(leftEsc); | ||
calibrateEsc(rightEsc); | ||
|
||
pinMode(pinDriveLeftDir, OUTPUT); | ||
pinMode(pinDriveLeftPwm, OUTPUT); | ||
pinMode(pinDriveLeftBrake, OUTPUT); | ||
pinMode(pinDriveLeftPower, OUTPUT); | ||
// Set ESC pins | ||
pinMode(ESC_LEFT_PWM, OUTPUT); | ||
pinMode(ESC_LEFT_POWER, OUTPUT); | ||
pinMode(ESC_RIGHT_PWM, OUTPUT); | ||
pinMode(ESC_RIGHT_POWER, OUTPUT); | ||
} | ||
|
||
void Drive::loop() { | ||
// Calculate turning speed | ||
int mappedThrottle = map(controller.control_CH1_roll, ESC_MIN_THROTTLE, ESC_MAX_THROTTLE, -500, 500); | ||
|
||
// Determine direction and adjust motor speeds | ||
if (controller.control_CH2_pitch >= ESC_IDLE_THROTTLE) { | ||
// Forward | ||
driveLeftSpeed = controller.control_CH2_pitch + mappedThrottle; | ||
driveRightSpeed = controller.control_CH2_pitch - mappedThrottle; | ||
} else { | ||
// Reverse | ||
driveLeftSpeed = controller.control_CH2_pitch - mappedThrottle; | ||
driveRightSpeed = controller.control_CH2_pitch + mappedThrottle; | ||
} | ||
|
||
// Constrain speed | ||
driveLeftSpeed = constrain(driveLeftSpeed, ESC_MIN_THROTTLE, ESC_MAX_THROTTLE); | ||
driveRightSpeed = constrain(driveRightSpeed, ESC_MIN_THROTTLE, ESC_MAX_THROTTLE); | ||
|
||
pinMode(pinDriveRightDir, OUTPUT); | ||
pinMode(pinDriveRightPwm, OUTPUT); | ||
pinMode(pinDriveRightBrake, OUTPUT); | ||
pinMode(pinDriveRightPower, OUTPUT); | ||
// Drive motors | ||
controlDriveMotor(driveLeftSpeed, leftEsc); | ||
controlDriveMotor(driveRightSpeed, rightEsc); | ||
|
||
Flysky::setup(); | ||
// Used for debugging control | ||
// Serial.print("Left speed = "); | ||
// Serial.print(driveLeftSpeed); | ||
// Serial.print(" | Right speed = "); | ||
// Serial.print(driveRightSpeed); | ||
// Serial.print(" | Roll = "); | ||
// Serial.print(controller.control_CH1_roll); | ||
// Serial.print(" | Pitch = "); | ||
// Serial.print(controller.control_CH2_pitch); | ||
// Serial.println(); | ||
|
||
Serial.println(F("Sending Flysky Config")); | ||
Serial1.begin(FLYSKY_BAUDRATE); | ||
ibus.begin(Serial1); | ||
delay(50); | ||
} | ||
|
||
void Drive::controlDriveLeftMotor(int speed, int direction) { | ||
if (direction == 0) { | ||
// reverse | ||
digitalWrite(pinDriveLeftDir, LOW); | ||
digitalWrite(pinDriveLeftBrake, HIGH); | ||
} else { | ||
// forward | ||
digitalWrite(pinDriveLeftDir, HIGH); | ||
digitalWrite(pinDriveLeftBrake, LOW); | ||
// Initialize ESC as bi-directional | ||
void Drive::calibrateEsc(Servo esc) { | ||
esc.writeMicroseconds(ESC_ARM_TIME); | ||
delay(ESC_ARM_TIME); | ||
esc.writeMicroseconds(ESC_MIN_THROTTLE); | ||
delay(ESC_ARM_TIME); | ||
esc.writeMicroseconds(ESC_IDLE_THROTTLE); | ||
delay(ESC_ARM_TIME); | ||
} | ||
|
||
// Controls supplied ESC by writing speed in microseconds | ||
void Drive::controlDriveMotor(int speed, Servo esc) { | ||
if (isDeadzone(speed)) { | ||
speed = ESC_IDLE_THROTTLE; | ||
} | ||
|
||
// control | ||
leftEsc.writeMicroseconds(speed); | ||
} | ||
int curSpeed = esc.readMicroseconds(); | ||
|
||
void Drive::controlDriveRightMotor(int speed, int direction) { | ||
if (direction == 0) { | ||
// reverse | ||
digitalWrite(pinDriveRightDir, LOW); | ||
digitalWrite(pinDriveRightBrake, HIGH); | ||
} else { | ||
// forward | ||
digitalWrite(pinDriveRightDir, HIGH); | ||
digitalWrite(pinDriveRightBrake, LOW); | ||
// The controller flutters signal occasionally +-10, so we do not write those flutters to the motor | ||
if (curSpeed < (speed - ESC_FLUTTER_RANGE) || curSpeed > (speed + ESC_FLUTTER_RANGE)) { | ||
esc.writeMicroseconds(speed); | ||
} | ||
} | ||
|
||
// control | ||
rightEsc.writeMicroseconds(speed); | ||
// Determines if speed falls between 1400 - 1600 | ||
// Ensures motors will not turn until joystick is pressed | ||
bool Drive::isDeadzone(int speed) { | ||
return (speed >= (ESC_IDLE_THROTTLE - ESC_DEADZONE_RANGE) && speed <= (ESC_IDLE_THROTTLE + ESC_DEADZONE_RANGE)); | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,43 +1,48 @@ | ||
#ifndef DRIVE_H | ||
#define DRIVE_H | ||
|
||
#include "flysky.h" | ||
#include "controller.h" | ||
#include <Arduino.h> | ||
#include <Servo.h> | ||
|
||
// pin defs | ||
#define pinDriveLeftDir 12 | ||
#define pinDriveLeftPwm 3 | ||
#define pinDriveLeftBrake 9 | ||
#define pinDriveLeftPower 4 | ||
|
||
#define pinDriveRightDir 13 | ||
#define pinDriveRightPwm 11 | ||
#define pinDriveRightBrake 8 | ||
#define pinDriveRightPower 10 | ||
|
||
// ESC | ||
extern Servo leftEsc; | ||
extern Servo rightEsc; | ||
|
||
// baudrates | ||
#define CONSOLE_BAUDRATE 19200 | ||
#define FLYSKY_BAUDRATE 115200 | ||
// pin defs | ||
#define ESC_LEFT_PWM 3 | ||
#define ESC_LEFT_POWER 4 | ||
|
||
#define ESC_RIGHT_PWM 11 | ||
#define ESC_RIGHT_POWER 10 | ||
|
||
// Throttle positions | ||
#define ESC_MIN_THROTTLE 1000 | ||
#define ESC_MAX_THROTTLE 2000 | ||
#define ESC_IDLE_THROTTLE 1500 | ||
|
||
// serial ports | ||
#define Console Serial | ||
#define Flyskyport Serial1 | ||
#define ESC_ARM_SIGNAL 1000 | ||
#define ESC_ARM_TIME 2000 | ||
|
||
class Drive : public Flysky { | ||
#define ESC_DEADZONE_RANGE 100 | ||
#define ESC_FLUTTER_RANGE 10 | ||
|
||
class Drive { | ||
public: | ||
// ESC motor speeds | ||
int driveLeftSpeed = 0; | ||
int driveRightSpeed = 0; | ||
|
||
Drive(); | ||
|
||
virtual void setup(void); | ||
virtual void loop(); | ||
|
||
virtual void controlDriveLeftMotor(int speed, int direction); | ||
virtual void controlDriveRightMotor(int speed, int direction); | ||
virtual void calibrateEsc(Servo esc); | ||
virtual void controlDriveMotor(int speed, Servo esc); | ||
virtual bool isDeadzone(int speed); | ||
}; | ||
|
||
extern Drive drive; | ||
|
||
#endif | ||
#endif // DRIVE_H |
Oops, something went wrong.