Skip to content

Commit

Permalink
multiple homing refinements
Browse files Browse the repository at this point in the history
  • Loading branch information
doudar committed Nov 9, 2024
1 parent 68fef39 commit 29b500d
Show file tree
Hide file tree
Showing 5 changed files with 56 additions and 71 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0
### Added

### Changed
- Multiple Homing refinements.

### Hardware

Expand Down
4 changes: 2 additions & 2 deletions include/settings.h
Original file line number Diff line number Diff line change
Expand Up @@ -312,8 +312,8 @@ const char* const DEFAULT_PASSWORD = "password";
#define BLE_RECONNECT_SCAN_DURATION 5

// Task Stack Sizes
#define MAIN_STACK 6000
#define BLE_CLIENT_STACK 5500
#define MAIN_STACK 6500
#define BLE_CLIENT_STACK 6000

// Uncomment to enable stack size debugging info
// #define DEBUG_STACK
Expand Down
3 changes: 1 addition & 2 deletions platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,7 @@ lib_deps =
https://github.com/h2zero/NimBLE-Arduino/archive/refs/tags/1.4.0.zip
https://github.com/teemuatlut/TMCStepper/archive/refs/tags/v0.7.3.zip
https://github.com/bblanchon/ArduinoJson/archive/refs/tags/v6.20.0.zip
https://github.com/witnessmenow/Universal-Arduino-Telegram-Bot/archive/refs/tags/V1.3.0.zip
https://github.com/gin66/FastAccelStepper/archive/refs/tags/0.28.3.zip
https://github.com/gin66/FastAccelStepper/archive/refs/tags/0.31.2.zip
https://github.com/gilmaimon/ArduinoWebsockets/archive/refs/tags/0.5.3.zip

[env:release]
Expand Down
3 changes: 0 additions & 3 deletions src/BLE_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,9 +96,6 @@ void BLECommunications() {

if (connectedClientCount() > 0 && !ss2k->isUpdating) {
spinBLEServer.update();
// if (spinDown()) {
// Possibly do something in the future. Right now we just fake the spin down.
// }

#ifdef INTERNAL_ERG_4EXT_FTMS
uint8_t test[] = {FitnessMachineControlPointProcedure::SetIndoorBikeSimulationParameters, 0x00, 0x00, 0x00, 0x00, 0x28, 0x33};
Expand Down
116 changes: 52 additions & 64 deletions src/Main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,11 @@ void setup() {
userConfig->printFile(); // Print userConfig->contents to serial
userConfig->saveToLittleFS();

// if we have homing data, use that instead.
if (userConfig->getHMax() != INT32_MIN && userConfig->getHMin() != INT32_MIN) {
spinBLEServer.spinDownFlag = 1;
}

// load PWC for HR to Pwr Calculation
userPWC->loadFromLittleFS();
userPWC->printFile();
Expand Down Expand Up @@ -161,10 +166,6 @@ void setup() {
&maintenanceLoopTask, /* Task handle to keep track of created task */
1); /* pin task to core */

// if we have homing data, use that instead.
if (userConfig->getHMax() != INT32_MIN && userConfig->getHMin() != INT32_MIN) {
spinBLEServer.spinDownFlag = 1;
}
}

void loop() { // Delete this task so we can make one that's more memory efficient.
Expand Down Expand Up @@ -195,7 +196,7 @@ void SS2K::maintenanceLoop(void *pvParameters) {
// If we're in ERG mode, modify shift commands to inc/dec the target watts instead.
ss2k->FTMSModeShiftModifier();
// If we have a resistance bike attached, slow down when we're close to the limits.
if (ss2k->pelotonIsConnected && !rtConfig->getHomed()) {
if (ss2k->pelotonIsConnected && !rtConfig->getHomed() && !spinBLEServer.spinDownFlag) {
int speed = userConfig->getStepperSpeed();
float resistance = rtConfig->resistance.getValue();
float maxResistance = rtConfig->getMaxResistance();
Expand Down Expand Up @@ -468,10 +469,6 @@ void SS2K::moveStepper() {
}

if (connectedClientCount() > 0) {
stepper->setAutoEnable(false); // Keep the stepper from rolling back due to head tube slack. Motor Driver still lowers power between moves
stepper->enableOutputs();
} else {
stepper->setAutoEnable(true); // disable output FETs between moves so stepper can cool. Can still shift.
}

if (_stepperDir != userConfig->getStepperDir()) { // User changed the config direction of the stepper wires
Expand Down Expand Up @@ -544,21 +541,20 @@ void SS2K::setupTMCStepperDriver(bool reset) {
stepper->setAutoEnable(true);
stepper->setSpeedInHz(DEFAULT_STEPPER_SPEED);
stepper->setAcceleration(STEPPER_ACCELERATION);
stepper->setDelayToDisable(1000);
stepper->setDelayToDisable(65535);
// TMC Driver Setup
driver.begin();
}

driver.pdn_disable(true);
driver.mstep_reg_select(true);
driver.microsteps(4); // Set microsteps to 1/8th
driver.iholddelay(10); // Controls the number of clock cycles for motor
// power down after standstill is detected
driver.TPOWERDOWN(128);
driver.toff(5);
driver.pdn_disable(true); // Use PDN pin to enable UART communication instead of grounding signal
driver.mstep_reg_select(true); // Use register instead of ms1&ms2 pins for microstep selection
driver.microsteps(4); // Set microsteps to 1/8th
driver.iholddelay(10); // Controls the number of clock cycles for motor power down after standstill is detected
driver.TPOWERDOWN(128); // delay until hold current
driver.toff(5); // needs >0 for driver enable. 1-15 controls duration of slow decay phase of pwm.
this->updateStealthChop();
driver.irun(currentBoard.pwrScaler);
driver.ihold((uint8_t)(currentBoard.pwrScaler * .5)); // hold current % 0-DRIVER_MAX_PWR_SCALER
driver.ihold((uint8_t)(currentBoard.pwrScaler * .1)); // hold current % 0-DRIVER_MAX_PWR_SCALER
this->updateStepperSpeed();
this->updateStepperPower();
this->setCurrentPosition(stepper->getCurrentPosition());
Expand All @@ -571,67 +567,33 @@ void SS2K::goHome(bool bothDirections) {
return;
}
SS2K_LOG(MAIN_LOG_TAG, "Homing...");
int _IFCNT = driver.IFCNT(); // Number of UART commands rx by driver
SS2K_LOG(MAIN_LOG_TAG, "Updating driver...");
updateStepperPower(100);
updateStepperPower(userConfig->getStepperPower()*.2);
vTaskDelay(50 / portTICK_PERIOD_MS);
driver.irun(2); // low power
driver.irun(0x02); // low power
vTaskDelay(50 / portTICK_PERIOD_MS);
driver.ihold((uint8_t)(1));
driver.ihold(0x01);
vTaskDelay(50 / portTICK_PERIOD_MS);
int threshold = 0;
bool stalled = false;
if (bothDirections) {
// Back off limit in case we are alread here.
stepper->move(-userConfig->getShiftStep());
while (stepper->isRunning()) {
vTaskDelay(50 / portTICK_PERIOD_MS);
}
this->updateStepperSpeed(1500);
vTaskDelay(500 / portTICK_PERIOD_MS);
stepper->runForward();
vTaskDelay(250 / portTICK_PERIOD_MS); // wait until stable
threshold = driver.SG_RESULT(); // take reading
Serial.printf("%d ", driver.SG_RESULT());
vTaskDelay(250 / portTICK_PERIOD_MS);
while (!stalled) {
if (abs(rtConfig->getShifterPosition() - ss2k->lastShifterPosition)) { // let the user abort with the shift button.
userConfig->setHMin(INT32_MIN);
userConfig->setHMax(INT32_MIN);
return;
}
stalled = (driver.SG_RESULT() < threshold - 100);
}
stalled = false;
stepper->forceStop();
stepper->disableOutputs();
vTaskDelay(2000 / portTICK_PERIOD_MS);
rtConfig->setMaxStep(stepper->getCurrentPosition() - 200);
SS2K_LOG(MAIN_LOG_TAG, "Max Position found: %d.", rtConfig->getMaxStep());
stepper->enableOutputs();
} else { // Back off limit in case we are alread here.
stepper->move(userConfig->getShiftStep());
while (stepper->isRunning()) {
vTaskDelay(50 / portTICK_PERIOD_MS);
}
this->updateStepperSpeed(1500);
vTaskDelay(500 / portTICK_PERIOD_MS);
}
// Back off limit in case we are alread here.
stepper->move(userConfig->getShiftStep(), true);
this->updateStepperSpeed(1500);
vTaskDelay(500 / portTICK_PERIOD_MS);
stepper->runBackward();
vTaskDelay(250 / portTICK_PERIOD_MS);
threshold = driver.SG_RESULT();
Serial.printf("%d ", driver.SG_RESULT());
vTaskDelay(250 / portTICK_PERIOD_MS);
vTaskDelay(300 / portTICK_PERIOD_MS);
while (!stalled) {
if (abs(rtConfig->getShifterPosition() - ss2k->lastShifterPosition)) { // let the user abort with the shift button.
userConfig->setHMin(INT32_MIN);
userConfig->setHMax(INT32_MIN);
return;
}
stalled = (driver.SG_RESULT() < threshold - 75);
stalled = (driver.SG_RESULT() < threshold - 50);
}
stepper->forceStop();
stepper->disableOutputs();
vTaskDelay(100 / portTICK_PERIOD_MS);
stepper->moveTo(stepper->getCurrentPosition() + userConfig->getShiftStep());
while (stepper->isRunning()) {
Expand All @@ -641,7 +603,32 @@ void SS2K::goHome(bool bothDirections) {
ss2k->setTargetPosition(0);
rtConfig->setMinStep(0);
SS2K_LOG(MAIN_LOG_TAG, "Min Position found: %d.", rtConfig->getMinStep());
stepper->enableOutputs();
stalled = false;

if (bothDirections) {
// Back off limit in case we are alread here.
this->updateStepperSpeed(1500);
vTaskDelay(500 / portTICK_PERIOD_MS);
stepper->runForward();
vTaskDelay(1000 / portTICK_PERIOD_MS); // wait until stable
threshold = driver.SG_RESULT(); // take reading
Serial.printf("%d ", driver.SG_RESULT());
vTaskDelay(250 / portTICK_PERIOD_MS);
while (!stalled) {
if (abs(rtConfig->getShifterPosition() - ss2k->lastShifterPosition)) { // let the user abort with the shift button.
userConfig->setHMin(INT32_MIN);
userConfig->setHMax(INT32_MIN);
return;
}
stalled = (driver.SG_RESULT() < threshold - 100);
}
stepper->forceStop();
vTaskDelay(1000 / portTICK_PERIOD_MS);
rtConfig->setMaxStep(stepper->getCurrentPosition() - 200);
SS2K_LOG(MAIN_LOG_TAG, "Max Position found: %d.", rtConfig->getMaxStep());
this->updateStepperSpeed();
stepper->moveTo(0, true);
}
}

// Start Saving Settings
Expand All @@ -654,14 +641,15 @@ void SS2K::goHome(bool bothDirections) {
userConfig->saveToLittleFS();
rtConfig->setHomed(true);
this->setupTMCStepperDriver(true);
ss2k->setTargetPosition(0);
}

// Applies current power to driver
void SS2K::updateStepperPower(int pwr) {
uint16_t rmsPwr = (pwr == 0) ? userConfig->getStepperPower() : pwr;
driver.rms_current(rmsPwr);
uint16_t current = driver.cs_actual();
SS2K_LOG(MAIN_LOG_TAG, "Stepper power is now %d. read:cs=%U", (pwr == 0) ? userConfig->getStepperPower() : pwr, current);
SS2K_LOG(MAIN_LOG_TAG, "Stepper power is now %d. read:cs=%U", rmsPwr, current);
}

// Applies current StealthChop to driver
Expand All @@ -677,8 +665,8 @@ void SS2K::updateStealthChop() {
void SS2K::updateStepperSpeed(int speed) {
if (speed == 0) {
speed = userConfig->getStepperSpeed();
SS2K_LOG(MAIN_LOG_TAG, "StepperSpeed is now %d", speed);
}
SS2K_LOG(MAIN_LOG_TAG, "StepperSpeed is now %d", speed);
stepper->setSpeedInHz(speed);
}

Expand Down

0 comments on commit 29b500d

Please sign in to comment.