Skip to content

Instantly share code, notes, and snippets.

@atc1441
Created June 10, 2019 12:50
Show Gist options
  • Save atc1441/b275e691e11b37876d5a94d09b715575 to your computer and use it in GitHub Desktop.
Save atc1441/b275e691e11b37876d5a94d09b715575 to your computer and use it in GitHub Desktop.
/*
* Test Code For Hoverboard with this firmware:
* https://github.com/p-h-a-i-l/hoverboard-firmware-hack
*
* Connect the PPM Receiver Data Pin to Arduino Pin 3
* And set the Amount of channels of the PPM Receiver.
* this code uses the Arduino Hardware serial.
*
*/
byte interruptPin = 3; // Arduino PPM Pin
byte channelAmount = 10; // PPM Channel count
#define SteerChannel 1
#define SpeedChannel 2
unsigned long minChannelValue = 1000;
unsigned long maxChannelValue = 2000;
unsigned long channelValueMaxError = 10;
unsigned long blankTime = 2100;
volatile unsigned long *rawValues = NULL;
volatile unsigned long *validValues = NULL;
volatile byte pulseCounter = 0;
volatile unsigned long microsAtLastPulse = 0;
typedef struct MsgToHoverboard_t {
unsigned char SOM;
unsigned char len;
unsigned char cmd;
unsigned char code;
int16_t base_pwm;
int16_t steer;
unsigned char CS;
};
typedef union UART_Packet_t {
MsgToHoverboard_t msgToHover;
byte UART_Packet[sizeof(MsgToHoverboard_t)];
};
void setHoverboardPWM( int16_t base_pwm, int16_t steer )
{
UART_Packet_t ups;
ups.msgToHover.SOM = 2 ; // PROTOCOL_SOM; //Start of Message;
ups.msgToHover.len = 7; // payload + SC only
ups.msgToHover.cmd = 'W'; // PROTOCOL_CMD_WRITEVAL; // Write value
ups.msgToHover.code = 0x07; // speed data from params array
ups.msgToHover.base_pwm = base_pwm;
ups.msgToHover.steer = steer;
ups.msgToHover.CS = 0;
for (int i = 0; i < ups.msgToHover.len; i++) {
ups.msgToHover.CS -= ups.UART_Packet[i + 1];
}
Serial.write(ups.UART_Packet, sizeof(UART_Packet_t));
}
void setup() {
PPMReader(interruptPin, channelAmount);
Serial.begin(115200);
}
void loop() {
int steer = map(latestValidChannelValue(SteerChannel, 0), 1100, 1900, -1000, 1000); // PPM CHANNEL 1 for Steering
int speed = map(latestValidChannelValue(SpeedChannel, 0), 1100, 1900, -1000, 1000); // PPM CHANNEL 2 for Speed
setHoverboardPWM(speed, steer);
delay(5);
}
void PPMReader(byte interruptPin, byte channelAmount) {
if (interruptPin > 0 && channelAmount > 0) {
rawValues = new unsigned long[channelAmount];
validValues = new unsigned long[channelAmount];
for (int i = 0; i < channelAmount; ++i) {
rawValues[i] = 1500;
validValues[i] = 1500;
}
pinMode(interruptPin, INPUT);
attachInterrupt(digitalPinToInterrupt(interruptPin), interruptfrompin, RISING);
}
}
void interruptfrompin() {
unsigned long previousMicros = microsAtLastPulse;
microsAtLastPulse = micros();
unsigned long time = microsAtLastPulse - previousMicros;
if (time > blankTime) {
pulseCounter = 0;
}
else {
if (pulseCounter < channelAmount) {
rawValues[pulseCounter] = time;
if (time >= minChannelValue - channelValueMaxError && time <= maxChannelValue + channelValueMaxError) {
validValues[pulseCounter] = constrain(time, minChannelValue, maxChannelValue);
}
}
++pulseCounter;
}
}
unsigned long rawChannelValue(byte channel) {
unsigned long value = 0;
if (channel >= 1 && channel <= channelAmount) {
noInterrupts();
value = rawValues[channel - 1];
interrupts();
}
return value;
}
unsigned long latestValidChannelValue(byte channel, unsigned long defaultValue) {
unsigned long value = defaultValue;
if (channel >= 1 && channel <= channelAmount) {
noInterrupts();
value = validValues[channel - 1];
interrupts();
}
return value;
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment