Closed Bastl1989 closed 1 month ago
So I found out: Setting to SPD_CTRL shows, the board has enough power! This is good :) DEFAULT_SPEED_COEFFICIENT increased from 16348 to 32000 --> now it has torque at 0rpm. (not full but it is ok for now) Btw. DEFAULT_SPEED_COEFFICIENT = max (65535) does not work. Wheels will not spin
What is the max value I should send for TRQ_CTRL? is 1000 the max value? as stated here? "It seems it is proportional to max current. eg 1000 = 100% * I_max"
Hi Bastl1989, I was working on a similar project and me too want to have a soft start. I want the acelleration to be more progressive so if the kid press the accelerator pedal all way down the acceleration is slow and speed rise form the curretn to the max value (set by the potentiometer) slovly not as a burst, I'm usinig the Hovercar version with sinusodial control. I'm trying to implement this in the code but your aproach seems to be simpler, may you share your Arduino code? Many thanks
Hi sure, as you will see, I just picked the provided basic code and updated it to my needs. Be aware to check the values for your accelerator pedal as mine has resistance that delivers ~180 to ~800 for 0 - 100%.
`// // Arduino Nano 5V example code // for https://github.com/EmanuelFeru/hoverboard-firmware-hack-FOC // // Copyright (C) 2019-2020 Emanuel FERU aerdronix@gmail.com // // // INFO: // • This sketch uses the the Serial Software interface to communicate and send commands to the hoverboard // • The built-in (HW) Serial interface is used for debugging and visualization. In case the debugging is not needed, // it is recommended to use the built-in Serial interface for full speed perfomace. // • The data packaging includes a Start Frame, checksum, and re-syncronization capability for reliable communication // // The code starts with zero speed and moves towards + // // CONFIGURATION on the hoverboard side in config.h: // • Option 1: Serial on Right Sensor cable (short wired cable) - recommended, since the USART3 pins are 5V tolerant.
// • Option 2: Serial on Left Sensor cable (long wired cable) - use only with 3.3V devices! The USART2 pins are not 5V tolerant! // #define CONTROL_SERIAL_USART2 // #define FEEDBACK_SERIAL_USART2 // // #define DEBUG_SERIAL_USART2 // ***
// ########################## DEFINES ##########################
//#define SPEED_MAX_TEST 150 // [-] Maximum speed for testing //#define SPEED_STEP 10 // [-] Speed step //#define DEBUG_RX // [-] Debug received data. Prints all bytes to serial (comment-out to disable)
// Achtung! A0 und A1 für Platine tauschen!
SoftwareSerial HoverSerial(2,3); // RX, TX
// Global variables uint8_t idx = 0; // Index for new data pointer uint16_t bufStartFrame; // Buffer Start Frame byte *p; // Pointer declaration for the new received data byte incomingByte; byte incomingBytePrev;
typedef struct{ uint16_t start; int16_t steer; int16_t speed; uint16_t checksum; } SerialCommand; SerialCommand Command;
typedef struct{ uint16_t start; int16_t cmd1; int16_t cmd2; int16_t speedR_meas; int16_t speedL_meas; int16_t batVoltage; int16_t boardTemp; uint16_t cmdLed; uint16_t checksum; } SerialFeedback; SerialFeedback Feedback; SerialFeedback NewFeedback;
//GLOBALS double vVehDiff = 0; double vVeh = 0; float trq = 0; double tchecklast = 0.0; double tchecklastFP = 0.0; unsigned long iTimeVehSpd = 0; unsigned long iTimeFP = 0; unsigned long iTimeGear = 0;
int rawval; float val; float val_o = 0; const float grad = 250; // very raw filtering of read poti value of accelerator pedal float trqFP = 0; // trq from Fahrpedal float trqFP_old = 0; // trq from Fahrpedal float trqSum = 0; // float trqSum_old = 0; float maxTrqVVeh = 0;
float prc = 0; float prcOut = 0; float L_Fahrpedal_x [] = {0, 3, 25, 50, 75, 100}; // Lookup table, 6 counts, X to be increasing! float L_Fahrpedal_y [] = {0, 0, 10, 30, 75, 100};// % of maxTrqVal
int vVehMax = 220;// Maximal Vehicle Speed for trqMax const float maxTrqVal = 1000; float L_vVehTrqMax_x [] = {-100, -80, -50, 0, 25, 50}; //vDiff float L_vVehTrqMax_y [] = {maxTrqVal, 800, 350, 0, -20, -100};
//const float maxRekuTrq = -500; //float L_RekuVVeh_x [] = {0, 15, 17, 25, 30, 100}; //vVeh //float L_RekuVVeh_y [] = {0, 0, 0, -20, -75, maxRekuTrq}; //reku Trq //float trqReku = 0.0;
float grdTrqLimUp = 50; float grdTrqLimDwn = -500; int gearDir = 1; //1...fwd 2...bck, dflt FWD int gearLeverPos = 1; // 1... fwd 2...bck int gearLeverPos_old = 1;
// ########################## SETUP ########################## void setup() { Serial.begin(SERIAL_BAUD); Serial.println("Hoverboard Serial v1.0");
HoverSerial.begin(HOVER_SERIAL_BAUD); pinMode(LED_BUILTIN, OUTPUT);
pinMode(readPoti,INPUT); //Fahrpedal
pinMode(A2,OUTPUT); //Gang D/R digitalWrite(A2,HIGH); pinMode(readGear,INPUT); //Gang D/R
}
// ########################## SEND ########################## void Send(int16_t uSteer, int16_t uSpeed) { // Create command Command.start = (uint16_t)START_FRAME; Command.steer = (int16_t)uSteer; Command.speed = (int16_t)uSpeed; Command.checksum = (uint16_t)(Command.start ^ Command.steer ^ Command.speed);
// Write to Serial HoverSerial.write((uint8_t *) &Command, sizeof(Command)); }
// ########################## RECEIVE ########################## void Receive() { // Check for new data availability in the Serial buffer if (HoverSerial.available()) { incomingByte = HoverSerial.read(); // Read the incoming byte bufStartFrame = ((uint16_t)(incomingByte) << 8) | incomingBytePrev; // Construct the start frame } else { return; }
// If DEBUG_RX is defined print all incoming bytes
// Serial.print("bufStartFrame: ");Serial.println(bufStartFrame); //Serial.print(incomingByte); return;
// Copy received data
if (bufStartFrame == START_FRAME) { // Initialize if new data is detected
p = (byte *)&NewFeedback;
*p++ = incomingBytePrev;
*p++ = incomingByte;
idx = 2;
} else if (idx >= 2 && idx < sizeof(SerialFeedback)) { // Save the new received data
*p++ = incomingByte;
idx++;
}
// Check if we reached the end of the package
if (idx == sizeof(SerialFeedback)) {
uint16_t checksum;
checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2 ^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas
^ NewFeedback.batVoltage ^ NewFeedback.boardTemp ^ NewFeedback.cmdLed);
// Check validity of the new data
if (NewFeedback.start == START_FRAME && checksum == NewFeedback.checksum) {
// Copy the new data
memcpy(&Feedback, &NewFeedback, sizeof(SerialFeedback));
// Print data to built-in Serial
// Serial.print("bufStartFrame: ");Serial.println(bufStartFrame);
// Serial.print("1: "); Serial.print(Feedback.cmd1); // Serial.print(" 2: "); Serial.print(Feedback.cmd2); // Serial.print(" 3: "); Serial.print(Feedback.speedR_meas); // Serial.print(" 4: "); Serial.print(Feedback.speedL_meas); // Serial.print(" 5: "); Serial.print(Feedback.batVoltage); // Serial.print(" 6: "); Serial.print(Feedback.boardTemp); // Serial.print(" 7: "); Serial.print(Feedback.cmdLed); // Serial.print(" 8: "); Serial.println(vVeh); } else { // Serial.println("Non-valid data skipped"); //WIEDER Aktivieren! } idx = 0; // Reset the index (it prevents to enter in this if condition in the next cycle) }
// Update previous states
incomingBytePrev = incomingByte;
}
//#### Vehicle Speed ###### /*Rechter Motor ist 3 (Vorwärts ist negativ)
*/ void vVehSpd(){ double speed_R; double speed_L;
speed_R = -Feedback.speedR_meas; //Right motor needs reverse in read speed speed_L = Feedback.speedL_meas;
vVeh = (speed_R + speed_L)/2; // Update in Future, for now ok
if (gearLeverPos == P_Global_reverse) { //bck demanded vVehDiff = -vVeh - vVehMax; } else{ vVehDiff = vVeh - vVehMax; // Difference speed to maxSpeed for trqLim. Negative is below limit, positibve is beyond limit } }
//########################## AcceleratorPedal ######################
void Fahrpedal() {
rawval = analogRead(readPoti); val = min(val_o+grad,rawval); val_o = val; prc = max(0,min(100,map(val,185,800,0,100))); // should build min/max learn function in future here
// Lookup Table int i = 0; for (i = 1; i<= 5;i++){ // counts 1,2,3,4,5
if(prc >= L_Fahrpedal_x[(i-1)] && prc < L_Fahrpedal_x[(i)]){ prcOut = map(prc,L_Fahrpedal_x[(i-1)],L_Fahrpedal_x[(i)],L_Fahrpedal_y[(i-1)],L_Fahrpedal_y[(i)]); } else if (prc < L_Fahrpedal_x[0]){ prcOut = L_Fahrpedal_y[0]; } else if (prc >= L_Fahrpedal_x[5]){ prcOut = L_Fahrpedal_y[5]; } }
trqFP = max(0,prcOut/100*maxTrqVal); // not limited, just raw driver request
trqFP_old = trqFP; //update old value. no function yet, maybe gradient limit or similar.
//Gradient limit for soft start // info: grdTrqLimUp is 50; grdTrqLimDwn = -500; every 150ms cyclic trqFP_old = max(trqFP_old + grdTrqLimDwn,min(trqFP_old+grdTrqLimUp,trqFP));
//Reduces torque max over vehicle speed i = 0; for (i = 1; i<= 6;i++){ if(vVehDiff >= L_vVehTrqMax_x[(i-1)] && vVehDiff < L_vVehTrqMax_x[(i)]){ maxTrqVVeh = map(vVehDiff,L_vVehTrqMax_x[(i-1)],L_vVehTrqMax_x[(i)],L_vVehTrqMax_y[(i-1)],L_vVehTrqMax_y[(i)]); } else if (vVehDiff < L_vVehTrqMax_x[0]){ maxTrqVVeh = L_vVehTrqMax_y[0]; } else if (vVehDiff >= L_vVehTrqMax_x[5]){ maxTrqVVeh = L_vVehTrqMax_y[5]; } }
trq = min(trqFP,maxTrqVVeh);
trqSum = trq; trqSum_old = trqSum;
// GearDir influence if(gearLeverPos == P_Global_reverse){ // Reverse trqSum = -trqSum; // Reverse TrqDir vVehMax = 80; //Set vMaxReverse } else{ vVehMax = 200; // Reset to vMaxForward }
}
//############### GEAR DET ###################
void GearDet() { if(abs(vVeh) <= 100){ // Change Vehicle Speed only below speed 100, abs, so that reverse also works gearLeverPos = digitalRead(readGear); // HIGH LOW (1..0), 1... swt to R } gearLeverPos_old = gearLeverPos; }
//##### PT-1 Filter############ unsigned long TimePT1 = 0; float pt1(float pt1_in,float pt1_out,float fac){ unsigned long timeNow_PT1 = millis(); if(TimePT1+10 > timeNow_PT1) return pt1_out; TimePT1 = timeNow_PT1; float out = 0; out = pt1_out+(pt1_in-pt1_out)*fac; return out; }
// ########################## LOOP ##########################
unsigned long iTimeSend = 0;
void loop(void) { unsigned long timeNow = millis();
// Check for new received data Receive();
//Check Gearlever if (iTimeGear> timeNow) return; //check if necessary to check iTimeGear = timeNow + 250; GearDet();
//Check Vehicle Speed if (iTimeVehSpd> timeNow) return; //check if necessary to check iTimeVehSpd = timeNow + 150; vVehSpd();
//Driver Torque Request if (iTimeFP> timeNow) return; //check if necessary to check iTimeFP = timeNow + 150; Fahrpedal();
// Send commands if (iTimeSend > timeNow) return; //check if necessary to check iTimeSend = timeNow + TIME_SEND; Send(0, trqSum); // Zero at Steer, trqSum for Drive
}
// ########################## END ##########################`
Dear Blast1989,
MANY THANKS I'm not sure this is what I'm trying to implement, I'll go through the code then I'll test it... Thank you again. Franco
Il giorno lun 7 ott 2024 alle ore 08:35 Bastl1989 @.***> ha scritto:
Hi sure, as you will see, I just picked the provided basic code and updated it to my needs. Be aware to check the values for your accelerator pedal as mine has resistance that delivers ~180 to ~800 for 0 - 100%.
`// ***** // Arduino Nano 5V example code // for https://github.com/EmanuelFeru/hoverboard-firmware-hack-FOC // // Copyright (C) 2019-2020 Emanuel FERU *@. // // *** // INFO: // • This sketch uses the the Serial Software interface to communicate and send commands to the hoverboard // • The built-in (HW) Serial interface is used for debugging and visualization. In case the debugging is not needed, // it is recommended to use the built-in Serial interface for full speed perfomace. // • The data packaging includes a Start Frame, checksum, and re-syncronization capability for reliable communication // // The code starts with zero speed and moves towards + // // CONFIGURATION on the hoverboard side in config.h: // • Option 1: Serial on Right Sensor cable (short wired cable) - recommended, since the USART3 pins are 5V tolerant.
define CONTROL_SERIAL_USART3
define FEEDBACK_SERIAL_USART3
define DEBUG_SERIAL_USART3
// • Option 2: Serial on Left Sensor cable (long wired cable) - use only with 3.3V devices! The USART2 pins are not 5V tolerant! // #define CONTROL_SERIAL_USART2 // #define FEEDBACK_SERIAL_USART2 // // #define DEBUG_SERIAL_USART2 // ***
// ########################## DEFINES ##########################
define HOVER_SERIAL_BAUD 115200 // [-] Baud rate for HoverSerial (used to
communicate with the hoverboard)
define SERIAL_BAUD 115200 // [-] Baud rate for built-in Serial (used for
the Serial Monitor)
define START_FRAME 0xABCD // [-] Start frme definition for reliable
serial communication
define TIME_SEND 100 // [ms] Sending time interval
//#define SPEED_MAX_TEST 150 // [-] Maximum speed for testing //#define SPEED_STEP 10 // [-] Speed step //#define DEBUG_RX // [-] Debug received data. Prints all bytes to serial (comment-out to disable)
define readPoti A0 // [-] Fahrpedal einlesen
define readGear A1 // Gang D/R Einlesen
// Achtung! A0 und A1 für Platine tauschen!
define P_Global_reverse 1
include
SoftwareSerial HoverSerial(2,3); // RX, TX
// Global variables uint8_t idx = 0; // Index for new data pointer uint16_t bufStartFrame; // Buffer Start Frame byte *p; // Pointer declaration for the new received data byte incomingByte; byte incomingBytePrev;
typedef struct{ uint16_t start; int16_t steer; int16_t speed; uint16_t checksum; } SerialCommand; SerialCommand Command;
typedef struct{ uint16_t start; int16_t cmd1; int16_t cmd2; int16_t speedR_meas; int16_t speedL_meas; int16_t batVoltage; int16_t boardTemp; uint16_t cmdLed; uint16_t checksum; } SerialFeedback; SerialFeedback Feedback; SerialFeedback NewFeedback;
//GLOBALS double vVehDiff = 0; double vVeh = 0; float trq = 0; double tchecklast = 0.0; double tchecklastFP = 0.0; unsigned long iTimeVehSpd = 0; unsigned long iTimeFP = 0; unsigned long iTimeGear = 0;
int rawval; float val; float val_o = 0; const float grad = 250; // very raw filtering of read poti value of accelerator pedal float trqFP = 0; // trq from Fahrpedal float trqFP_old = 0; // trq from Fahrpedal float trqSum = 0; // float trqSum_old = 0; float maxTrqVVeh = 0;
float prc = 0; float prcOut = 0; float L_Fahrpedal_x [] = {0, 3, 25, 50, 75, 100}; // Lookup table, 6 counts, X to be increasing! float L_Fahrpedal_y [] = {0, 0, 10, 30, 75, 100};// % of maxTrqVal
int vVehMax = 220;// Maximal Vehicle Speed for trqMax const float maxTrqVal = 1000; float L_vVehTrqMax_x [] = {-100, -80, -50, 0, 25, 50}; //vDiff float L_vVehTrqMax_y [] = {maxTrqVal, 800, 350, 0, -20, -100};
//const float maxRekuTrq = -500; //float L_RekuVVeh_x [] = {0, 15, 17, 25, 30, 100}; //vVeh //float L_RekuVVeh_y [] = {0, 0, 0, -20, -75, maxRekuTrq}; //reku Trq //float trqReku = 0.0;
float grdTrqLimUp = 50; float grdTrqLimDwn = -500; int gearDir = 1; //1...fwd 2...bck, dflt FWD int gearLeverPos = 1; // 1... fwd 2...bck int gearLeverPos_old = 1;
// ########################## SETUP ########################## void setup() { Serial.begin(SERIAL_BAUD); Serial.println("Hoverboard Serial v1.0");
HoverSerial.begin(HOVER_SERIAL_BAUD); pinMode(LED_BUILTIN, OUTPUT);
pinMode(readPoti,INPUT); //Fahrpedal
pinMode(A2,OUTPUT); //Gang D/R digitalWrite(A2,HIGH); pinMode(readGear,INPUT); //Gang D/R
}
// ########################## SEND ########################## void Send(int16_t uSteer, int16_t uSpeed) { // Create command Command.start = (uint16_t)START_FRAME; Command.steer = (int16_t)uSteer; Command.speed = (int16_t)uSpeed; Command.checksum = (uint16_t)(Command.start ^ Command.steer ^ Command.speed);
// Write to Serial HoverSerial.write((uint8_t *) &Command, sizeof(Command)); }
// ########################## RECEIVE ########################## void Receive() { // Check for new data availability in the Serial buffer if (HoverSerial.available()) { incomingByte = HoverSerial.read(); // Read the incoming byte bufStartFrame = ((uint16_t)(incomingByte) << 8) | incomingBytePrev; // Construct the start frame } else { return; }
// If DEBUG_RX is defined print all incoming bytes
ifdef DEBUG_RX
// Serial.print("bufStartFrame: ");Serial.println(bufStartFrame); //Serial.print(incomingByte); return;
endif
// Copy received data if (bufStartFrame == START_FRAME) { // Initialize if new data is detected p = (byte )&NewFeedback; p++ = incomingBytePrev; p++ = incomingByte; idx = 2; } else if (idx >= 2 && idx < sizeof(SerialFeedback)) { // Save the new received data p++ = incomingByte; idx++; }
// Check if we reached the end of the package if (idx == sizeof(SerialFeedback)) { uint16_t checksum; checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2 ^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas ^ NewFeedback.batVoltage ^ NewFeedback.boardTemp ^ NewFeedback.cmdLed);
// Check validity of the new data if (NewFeedback.start == START_FRAME && checksum == NewFeedback.checksum) { // Copy the new data memcpy(&Feedback, &NewFeedback, sizeof(SerialFeedback)); // Print data to built-in Serial // Serial.print("bufStartFrame: ");Serial.println(bufStartFrame);
// Serial.print("1: "); Serial.print(Feedback.cmd1); // Serial.print(" 2: "); Serial.print(Feedback.cmd2); // Serial.print(" 3: "); Serial.print(Feedback.speedR_meas); // Serial.print(" 4: "); Serial.print(Feedback.speedL_meas); // Serial.print(" 5: "); Serial.print(Feedback.batVoltage); // Serial.print(" 6: "); Serial.print(Feedback.boardTemp); // Serial.print(" 7: "); Serial.print(Feedback.cmdLed); // Serial.print(" 8: "); Serial.println(vVeh); } else { // Serial.println("Non-valid data skipped"); //WIEDER Aktivieren! } idx = 0; // Reset the index (it prevents to enter in this if condition in the next cycle) }
// Update previous states incomingBytePrev = incomingByte;
}
//#### Vehicle Speed ###### /*Rechter Motor ist 3 (Vorwärts ist negativ)
- Linker Motor ist 4 (Vorwärts ist Positiv)
*/ void vVehSpd(){ double speed_R; double speed_L;
speed_R = -Feedback.speedR_meas; //Right motor needs reverse in read speed speed_L = Feedback.speedL_meas;
vVeh = (speed_R + speed_L)/2; // Update in Future, for now ok
if (gearLeverPos == P_Global_reverse) { //bck demanded vVehDiff = -vVeh - vVehMax; } else{ vVehDiff = vVeh - vVehMax; // Difference speed to maxSpeed for trqLim. Negative is below limit, positibve is beyond limit } }
//########################## AcceleratorPedal ######################
void Fahrpedal() {
rawval = analogRead(readPoti); val = min(val_o+grad,rawval); val_o = val; prc = max(0,min(100,map(val,185,800,0,100))); // should build min/max learn function in future here
// Lookup Table int i = 0; for (i = 1; i<= 5;i++){ // counts 1,2,3,4,5
if(prc >= L_Fahrpedal_x[(i-1)] && prc < L_Fahrpedal_x[(i)]){ prcOut = map(prc,L_Fahrpedal_x[(i-1)],L_Fahrpedal_x[(i)],L_Fahrpedal_y[(i-1)],L_Fahrpedal_y[(i)]); } else if (prc < L_Fahrpedal_x[0]){ prcOut = L_Fahrpedal_y[0]; } else if (prc >= L_Fahrpedal_x[5]){ prcOut = L_Fahrpedal_y[5]; } }
trqFP = max(0,prcOut/100*maxTrqVal); // not limited, just raw driver request
trqFP_old = trqFP; //update old value. no function yet, maybe gradient limit or similar.
//Gradient limit for soft start // info: grdTrqLimUp is 50; grdTrqLimDwn = -500; every 150ms cyclic trqFP_old = max(trqFP_old + grdTrqLimDwn,min(trqFP_old+grdTrqLimUp,trqFP));
//Reduces torque max over vehicle speed i = 0; for (i = 1; i<= 6;i++){ if(vVehDiff >= L_vVehTrqMax_x[(i-1)] && vVehDiff < L_vVehTrqMax_x[(i)]){ maxTrqVVeh = map(vVehDiff,L_vVehTrqMax_x[(i-1)],L_vVehTrqMax_x[(i)],L_vVehTrqMax_y[(i-1)],L_vVehTrqMax_y[(i)]); } else if (vVehDiff < L_vVehTrqMax_x[0]){ maxTrqVVeh = L_vVehTrqMax_y[0]; } else if (vVehDiff >= L_vVehTrqMax_x[5]){ maxTrqVVeh = L_vVehTrqMax_y[5]; } }
trq = min(trqFP,maxTrqVVeh);
trqSum = trq; trqSum_old = trqSum;
// GearDir influence if(gearLeverPos == P_Global_reverse){ // Reverse trqSum = -trqSum; // Reverse TrqDir vVehMax = 80; //Set vMaxReverse } else{ vVehMax = 200; // Reset to vMaxForward }
}
//############### GEAR DET ###################
void GearDet() { if(abs(vVeh) <= 100){ // Change Vehicle Speed only below speed 100, abs, so that reverse also works gearLeverPos = digitalRead(readGear); // HIGH LOW (1..0), 1... swt to R } gearLeverPos_old = gearLeverPos; }
//##### PT-1 Filter############ unsigned long TimePT1 = 0; float pt1(float pt1_in,float pt1_out,float fac){ unsigned long timeNow_PT1 = millis(); if(TimePT1+10 > timeNow_PT1) return pt1_out; TimePT1 = timeNow_PT1; float out = 0; out = pt1_out+(pt1_in-pt1_out)*fac; return out; }
// ########################## LOOP ##########################
unsigned long iTimeSend = 0;
void loop(void) { unsigned long timeNow = millis();
// Check for new received data Receive();
//Check Gearlever if (iTimeGear> timeNow) return; //check if necessary to check iTimeGear = timeNow + 250; GearDet();
//Check Vehicle Speed if (iTimeVehSpd> timeNow) return; //check if necessary to check iTimeVehSpd = timeNow + 150; vVehSpd();
//Driver Torque Request if (iTimeFP> timeNow) return; //check if necessary to check iTimeFP = timeNow + 150; Fahrpedal();
// Send commands if (iTimeSend > timeNow) return; //check if necessary to check iTimeSend = timeNow + TIME_SEND; Send(0, trqSum); // Zero at Steer, trqSum for Drive
}
// ########################## END ##########################`
— Reply to this email directly, view it on GitHub https://github.com/EFeru/hoverboard-firmware-hack-FOC/issues/515#issuecomment-2396022437, or unsubscribe https://github.com/notifications/unsubscribe-auth/ACDNGYQBRPJHWBUTQ4AQAGTZ2ITURAVCNFSM6AAAAABO72TPZCVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMZDGOJWGAZDENBTG4 . You are receiving this because you commented.Message ID: @.***>
Variant
USART
Control type
FOC
Control mode
Torque
Description
Hello fellas! I know, I know - and yes I have read all the reported issues on low torque at low speeds. I just could not find a proper solution for my project.
To the project - I rebuilt an PegPerego-KidsCar for my daughter as I could not stand the whining noise of the original motors and gearbox anymore :) Also the offroad capabilities were very low. Grass was allready hard to handle. The vehicle now has suspension and uses the hoverboard motors on the rear.
I use torque control for drivability, and I read in the accelerator pedal (potentiometer) by arduino uno. I activated ELECTRIC_BRAKE with 250 and a threshold of 120.
I programmed an LookupTable in Arduino for the AcceleratorPedal (no torque-steering for now), and reducing it over read back speed (rpm_left + rpm_right)/2 for now. (More logic will follow whenever in need ;) )
I will send up to Send(0, 1300) for Send(Steer,Throttle) at launch. As soon as the wheel spins minimal rpm, power is there. But at standstill, nearly no power at all. That means no uphill launch possible :(
I_MOT_MAX 15 (as default) I_DC_MAX 17 (as default)
Do you have any Idea that could help me? Is there some kind of stall-protection that limits the current at 0 rpm? And how high can I tweak these numbers to not burn my board? My daughter loves her car and I do not want to break it.. Thank you!