Tweak STM32F7 TMC2660 class

This commit is contained in:
Scott Lahteine 2018-09-27 21:12:10 -05:00
parent a0a3b23e35
commit b682a1961a
2 changed files with 136 additions and 138 deletions

View File

@ -87,7 +87,7 @@
#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60ul #define SE_CURRENT_STEP_WIDTH_PATTERN 0x60ul
#define SE_MIN_PATTERN 0xFul #define SE_MIN_PATTERN 0xFul
//definitions for stall guard2 current register //definitions for StallGuard2 current register
#define STALL_GUARD_FILTER_ENABLED 0x10000ul #define STALL_GUARD_FILTER_ENABLED 0x10000ul
#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul #define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
#define CURRENT_SCALING_PATTERN 0x1Ful #define CURRENT_SCALING_PATTERN 0x1Ful
@ -118,7 +118,7 @@ SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN);
//#define TMC_DEBUG1 //#define TMC_DEBUG1
unsigned char current_scaling = 0; uint8_t current_scaling = 0;
/** /**
* Constructor * Constructor
@ -127,7 +127,7 @@ unsigned char current_scaling = 0;
* dir_pin - the pin where the direction pin is connected * dir_pin - the pin where the direction pin is connected
* step_pin - the pin where the step pin is connected * step_pin - the pin where the step pin is connected
*/ */
TMC26XStepper::TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor) { TMC26XStepper::TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) {
// We are not started yet // We are not started yet
started = false; started = false;
@ -155,7 +155,7 @@ TMC26XStepper::TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int s
microsteps = _BV(INITIAL_MICROSTEPPING); microsteps = _BV(INITIAL_MICROSTEPPING);
chopper_config_register = CHOPPER_CONFIG_REGISTER; chopper_config_register = CHOPPER_CONFIG_REGISTER;
cool_step_register_value = COOL_STEP_REGISTER; cool_step_register_value = COOL_STEP_REGISTER;
stall_guard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER; stallguard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER;
driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING; driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING;
// Set the current // Set the current
@ -202,7 +202,7 @@ void TMC26XStepper::start() {
send262(driver_control_register_value); send262(driver_control_register_value);
send262(chopper_config_register); send262(chopper_config_register);
send262(cool_step_register_value); send262(cool_step_register_value);
send262(stall_guard2_current_register_value); send262(stallguard2_current_register_value);
send262(driver_configuration_register_value); send262(driver_configuration_register_value);
//save that we are in running mode //save that we are in running mode
@ -218,9 +218,9 @@ void TMC26XStepper::un_start() { started = false; }
/** /**
* Sets the speed in revs per minute * Sets the speed in revs per minute
*/ */
void TMC26XStepper::setSpeed(unsigned int whatSpeed) { void TMC26XStepper::setSpeed(uint16_t whatSpeed) {
this->speed = whatSpeed; this->speed = whatSpeed;
this->step_delay = 60UL * sq(1000UL) / ((unsigned long)this->number_of_steps * (unsigned long)whatSpeed * (unsigned long)this->microsteps); this->step_delay = 60UL * sq(1000UL) / ((uint32_t)this->number_of_steps * (uint32_t)whatSpeed * (uint32_t)this->microsteps);
#ifdef TMC_DEBUG0 // crashes #ifdef TMC_DEBUG0 // crashes
//SERIAL_PRINTF("Step delay in micros: "); //SERIAL_PRINTF("Step delay in micros: ");
SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay); SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay);
@ -229,13 +229,13 @@ void TMC26XStepper::setSpeed(unsigned int whatSpeed) {
this->next_step_time = this->last_step_time + this->step_delay; this->next_step_time = this->last_step_time + this->step_delay;
} }
unsigned int TMC26XStepper::getSpeed(void) { return this->speed; } uint16_t TMC26XStepper::getSpeed(void) { return this->speed; }
/** /**
* Moves the motor steps_to_move steps. * Moves the motor steps_to_move steps.
* Negative indicates the reverse direction. * Negative indicates the reverse direction.
*/ */
char TMC26XStepper::step(int steps_to_move) { char TMC26XStepper::step(int16_t steps_to_move) {
if (this->steps_left == 0) { if (this->steps_left == 0) {
this->steps_left = ABS(steps_to_move); // how many steps to take this->steps_left = ABS(steps_to_move); // how many steps to take
@ -252,7 +252,7 @@ char TMC26XStepper::step(int steps_to_move) {
char TMC26XStepper::move(void) { char TMC26XStepper::move(void) {
// decrement the number of steps, moving one step each time: // decrement the number of steps, moving one step each time:
if (this->steps_left > 0) { if (this->steps_left > 0) {
unsigned long time = micros(); uint32_t time = micros();
// move only if the appropriate delay has passed: // move only if the appropriate delay has passed:
// rem if (time >= this->next_step_time) { // rem if (time >= this->next_step_time) {
@ -282,7 +282,7 @@ char TMC26XStepper::move(void) {
char TMC26XStepper::isMoving(void) { return this->steps_left > 0; } char TMC26XStepper::isMoving(void) { return this->steps_left > 0; }
unsigned int TMC26XStepper::getStepsLeft(void) { return this->steps_left; } uint16_t TMC26XStepper::getStepsLeft(void) { return this->steps_left; }
char TMC26XStepper::stop(void) { char TMC26XStepper::stop(void) {
//note to self if the motor is currently moving //note to self if the motor is currently moving
@ -294,8 +294,8 @@ char TMC26XStepper::stop(void) {
return state; return state;
} }
void TMC26XStepper::setCurrent(unsigned int current) { void TMC26XStepper::setCurrent(uint16_t current) {
unsigned char current_scaling = 0; uint8_t current_scaling = 0;
//calculate the current scaling from the max current setting (in mA) //calculate the current scaling from the max current setting (in mA)
float mASetting = (float)current, float mASetting = (float)current,
resistor_value = (float)this->resistor; resistor_value = (float)this->resistor;
@ -327,49 +327,49 @@ void TMC26XStepper::setCurrent(unsigned int current) {
NOMORE(current_scaling, 31); NOMORE(current_scaling, 31);
// delete the old value // delete the old value
stall_guard2_current_register_value &= ~(CURRENT_SCALING_PATTERN); stallguard2_current_register_value &= ~(CURRENT_SCALING_PATTERN);
// set the new current scaling // set the new current scaling
stall_guard2_current_register_value |= current_scaling; stallguard2_current_register_value |= current_scaling;
// if started we directly send it to the motor // if started we directly send it to the motor
if (started) { if (started) {
send262(driver_configuration_register_value); send262(driver_configuration_register_value);
send262(stall_guard2_current_register_value); send262(stallguard2_current_register_value);
} }
} }
unsigned int TMC26XStepper::getCurrent(void) { uint16_t TMC26XStepper::getCurrent(void) {
// Calculate the current according to the datasheet to be on the safe side. // Calculate the current according to the datasheet to be on the safe side.
// This is not the fastest but the most accurate and illustrative way. // This is not the fastest but the most accurate and illustrative way.
float result = (float)(stall_guard2_current_register_value & CURRENT_SCALING_PATTERN), float result = (float)(stallguard2_current_register_value & CURRENT_SCALING_PATTERN),
resistor_value = (float)this->resistor, resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31; voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (unsigned int)result; return (uint16_t)result;
} }
void TMC26XStepper::setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled) { void TMC26XStepper::setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled) {
// We just have 5 bits // We just have 5 bits
LIMIT(stall_guard_threshold, -64, 63); LIMIT(stallguard_threshold, -64, 63);
// Add trim down to 7 bits // Add trim down to 7 bits
stall_guard_threshold &= 0x7F; stallguard_threshold &= 0x7F;
// Delete old stall guard settings // Delete old StallGuard settings
stall_guard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN); stallguard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN);
if (stall_guard_filter_enabled) if (stallguard_filter_enabled)
stall_guard2_current_register_value |= STALL_GUARD_FILTER_ENABLED; stallguard2_current_register_value |= STALL_GUARD_FILTER_ENABLED;
// Set the new stall guard threshold // Set the new StallGuard threshold
stall_guard2_current_register_value |= (((unsigned long)stall_guard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN); stallguard2_current_register_value |= (((uint32_t)stallguard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN);
// If started we directly send it to the motor // If started we directly send it to the motor
if (started) send262(stall_guard2_current_register_value); if (started) send262(stallguard2_current_register_value);
} }
char TMC26XStepper::getStallGuardThreshold(void) { char TMC26XStepper::getStallGuardThreshold(void) {
unsigned long stall_guard_threshold = stall_guard2_current_register_value & STALL_GUARD_VALUE_PATTERN; uint32_t stallguard_threshold = stallguard2_current_register_value & STALL_GUARD_VALUE_PATTERN;
//shift it down to bit 0 //shift it down to bit 0
stall_guard_threshold >>= 8; stallguard_threshold >>= 8;
//convert the value to an int to correctly handle the negative numbers //convert the value to an int16_t to correctly handle the negative numbers
char result = stall_guard_threshold; char result = stallguard_threshold;
//check if it is negative and fill it up with leading 1 for proper negative number representation //check if it is negative and fill it up with leading 1 for proper negative number representation
//rem if (result & _BV(6)) { //rem if (result & _BV(6)) {
@ -378,7 +378,7 @@ char TMC26XStepper::getStallGuardThreshold(void) {
} }
char TMC26XStepper::getStallGuardFilter(void) { char TMC26XStepper::getStallGuardFilter(void) {
if (stall_guard2_current_register_value & STALL_GUARD_FILTER_ENABLED) if (stallguard2_current_register_value & STALL_GUARD_FILTER_ENABLED)
return -1; return -1;
return 0; return 0;
} }
@ -389,7 +389,7 @@ char TMC26XStepper::getStallGuardFilter(void) {
* any value in between will be mapped to the next smaller value * any value in between will be mapped to the next smaller value
* 0 and 1 set the motor in full step mode * 0 and 1 set the motor in full step mode
*/ */
void TMC26XStepper::setMicrosteps(int number_of_steps) { void TMC26XStepper::setMicrosteps(int16_t number_of_steps) {
long setting_pattern; long setting_pattern;
//poor mans log //poor mans log
if (number_of_steps >= 256) { if (number_of_steps >= 256) {
@ -448,7 +448,7 @@ void TMC26XStepper::setMicrosteps(int number_of_steps) {
/** /**
* returns the effective number of microsteps at the moment * returns the effective number of microsteps at the moment
*/ */
int TMC26XStepper::getMicrosteps(void) { return microsteps; } int16_t TMC26XStepper::getMicrosteps(void) { return microsteps; }
/** /**
* constant_off_time: The off time setting controls the minimum chopper frequency. * constant_off_time: The off time setting controls the minimum chopper frequency.
@ -473,7 +473,7 @@ int TMC26XStepper::getMicrosteps(void) { return microsteps; }
* 1: enable comparator termination of fast decay cycle * 1: enable comparator termination of fast decay cycle
* 0: end by time only * 0: end by time only
*/ */
void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator) { void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator) {
// Perform some sanity checks // Perform some sanity checks
LIMIT(constant_off_time, 2, 15); LIMIT(constant_off_time, 2, 15);
@ -497,16 +497,16 @@ void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank
// Set the constant off pattern // Set the constant off pattern
chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY; chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY;
// Set the blank timing value // Set the blank timing value
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
// Setting the constant off time // Setting the constant off time
chopper_config_register |= constant_off_time; chopper_config_register |= constant_off_time;
// Set the fast decay time // Set the fast decay time
// Set msb // Set msb
chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT); chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT);
// Other bits // Other bits
chopper_config_register |= (((unsigned long)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT); chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT);
// Set the sine wave offset // Set the sine wave offset
chopper_config_register |= (unsigned long)sine_wave_offset << HYSTERESIS_LOW_SHIFT; chopper_config_register |= (uint32_t)sine_wave_offset << HYSTERESIS_LOW_SHIFT;
// Using the current comparator? // Using the current comparator?
if (!use_current_comparator) if (!use_current_comparator)
chopper_config_register |= _BV(12); chopper_config_register |= _BV(12);
@ -564,15 +564,15 @@ void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_tim
chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN); chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
//set the blank timing value //set the blank timing value
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
//setting the constant off time //setting the constant off time
chopper_config_register |= constant_off_time; chopper_config_register |= constant_off_time;
//set the hysteresis_start //set the hysteresis_start
chopper_config_register |= ((unsigned long)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT; chopper_config_register |= ((uint32_t)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT;
//set the hysteresis end //set the hysteresis end
chopper_config_register |= ((unsigned long)hysteresis_end) << HYSTERESIS_LOW_SHIFT; chopper_config_register |= ((uint32_t)hysteresis_end) << HYSTERESIS_LOW_SHIFT;
//set the hystereis decrement //set the hystereis decrement
chopper_config_register |= ((unsigned long)blank_value) << BLANK_TIMING_SHIFT; chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
//if started we directly send it to the motor //if started we directly send it to the motor
if (started) { if (started) {
//rem send262(driver_control_register_value); //rem send262(driver_control_register_value);
@ -605,12 +605,12 @@ void TMC26XStepper::setRandomOffTime(char value) {
} }
void TMC26XStepper::setCoolStepConfiguration( void TMC26XStepper::setCoolStepConfiguration(
unsigned int lower_SG_threshold, uint16_t lower_SG_threshold,
unsigned int SG_hysteresis, uint16_t SG_hysteresis,
unsigned char current_decrement_step_size, uint8_t current_decrement_step_size,
unsigned char current_increment_step_size, uint8_t current_increment_step_size,
unsigned char lower_current_limit) uint8_t lower_current_limit
{ ) {
// Sanitize the input values // Sanitize the input values
NOMORE(lower_SG_threshold, 480); NOMORE(lower_SG_threshold, 480);
// Divide by 32 // Divide by 32
@ -628,11 +628,11 @@ void TMC26XStepper::setCoolStepConfiguration(
if (!this->cool_step_enabled) lower_SG_threshold = 0; if (!this->cool_step_enabled) lower_SG_threshold = 0;
// The good news is that we can start with a complete new cool step register value // The good news is that we can start with a complete new cool step register value
// And simply set the values in the register // And simply set the values in the register
cool_step_register_value = ((unsigned long)lower_SG_threshold) cool_step_register_value = ((uint32_t)lower_SG_threshold)
| (((unsigned long)SG_hysteresis) << 8) | (((uint32_t)SG_hysteresis) << 8)
| (((unsigned long)current_decrement_step_size) << 5) | (((uint32_t)current_decrement_step_size) << 5)
| (((unsigned long)current_increment_step_size) << 13) | (((uint32_t)current_increment_step_size) << 13)
| (((unsigned long)lower_current_limit) << 15) | (((uint32_t)lower_current_limit) << 15)
| COOL_STEP_REGISTER; // Register signature | COOL_STEP_REGISTER; // Register signature
//SERIAL_PRINTFln(cool_step_register_value,HEX); //SERIAL_PRINTFln(cool_step_register_value,HEX);
@ -653,25 +653,25 @@ void TMC26XStepper::setCoolStepEnabled(boolean enabled) {
boolean TMC26XStepper::isCoolStepEnabled(void) { return this->cool_step_enabled; } boolean TMC26XStepper::isCoolStepEnabled(void) { return this->cool_step_enabled; }
unsigned int TMC26XStepper::getCoolStepLowerSgThreshold() { uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() {
// We return our internally stored value - in order to provide the correct setting even if cool step is not enabled // We return our internally stored value - in order to provide the correct setting even if cool step is not enabled
return this->cool_step_lower_threshold<<5; return this->cool_step_lower_threshold<<5;
} }
unsigned int TMC26XStepper::getCoolStepUpperSgThreshold() { uint16_t TMC26XStepper::getCoolStepUpperSgThreshold() {
return (unsigned char)((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5; return (uint8_t)((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5;
} }
unsigned char TMC26XStepper::getCoolStepCurrentIncrementSize() { uint8_t TMC26XStepper::getCoolStepCurrentIncrementSize() {
return (unsigned char)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13); return (uint8_t)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13);
} }
unsigned char TMC26XStepper::getCoolStepNumberOfSGReadings() { uint8_t TMC26XStepper::getCoolStepNumberOfSGReadings() {
return (unsigned char)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5); return (uint8_t)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5);
} }
unsigned char TMC26XStepper::getCoolStepLowerCurrentLimit() { uint8_t TMC26XStepper::getCoolStepLowerCurrentLimit() {
return (unsigned char)((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15); return (uint8_t)((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15);
} }
void TMC26XStepper::setEnabled(boolean enabled) { void TMC26XStepper::setEnabled(boolean enabled) {
@ -693,7 +693,7 @@ boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_P
* *
*/ */
void TMC26XStepper::readStatus(char read_value) { void TMC26XStepper::readStatus(char read_value) {
unsigned long old_driver_configuration_register_value = driver_configuration_register_value; uint32_t old_driver_configuration_register_value = driver_configuration_register_value;
//reset the readout configuration //reset the readout configuration
driver_configuration_register_value &= ~(READ_SELECTION_PATTERN); driver_configuration_register_value &= ~(READ_SELECTION_PATTERN);
//this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options //this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options
@ -712,42 +712,42 @@ void TMC26XStepper::readStatus(char read_value) {
send262(driver_configuration_register_value); send262(driver_configuration_register_value);
} }
int TMC26XStepper::getMotorPosition(void) { int16_t TMC26XStepper::getMotorPosition(void) {
//we read it out even if we are not started yet - perhaps it is useful information for somebody //we read it out even if we are not started yet - perhaps it is useful information for somebody
readStatus(TMC26X_READOUT_POSITION); readStatus(TMC26X_READOUT_POSITION);
return getReadoutValue(); return getReadoutValue();
} }
//reads the stall guard setting from last status //reads the StallGuard setting from last status
//returns -1 if stallguard information is not present //returns -1 if StallGuard information is not present
int TMC26XStepper::getCurrentStallGuardReading(void) { int16_t TMC26XStepper::getCurrentStallGuardReading(void) {
//if we don't yet started there cannot be a stall guard value //if we don't yet started there cannot be a StallGuard value
if (!started) return -1; if (!started) return -1;
//not time optimal, but solution optiomal: //not time optimal, but solution optiomal:
//first read out the stall guard value //first read out the StallGuard value
readStatus(TMC26X_READOUT_STALLGUARD); readStatus(TMC26X_READOUT_STALLGUARD);
return getReadoutValue(); return getReadoutValue();
} }
unsigned char TMC26XStepper::getCurrentCSReading(void) { uint8_t TMC26XStepper::getCurrentCSReading(void) {
//if we don't yet started there cannot be a stall guard value //if we don't yet started there cannot be a StallGuard value
if (!started) return 0; if (!started) return 0;
//not time optimal, but solution optiomal: //not time optimal, but solution optiomal:
//first read out the stall guard value //first read out the StallGuard value
readStatus(TMC26X_READOUT_CURRENT); readStatus(TMC26X_READOUT_CURRENT);
return (getReadoutValue() & 0x1F); return (getReadoutValue() & 0x1F);
} }
unsigned int TMC26XStepper::getCurrentCurrent(void) { uint16_t TMC26XStepper::getCurrentCurrent(void) {
float result = (float)getCurrentCSReading(), float result = (float)getCurrentCSReading(),
resistor_value = (float)this->resistor, resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31; voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0); result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (unsigned int)result; return (uint16_t)result;
} }
/** /**
* Return true if the stallguard threshold has been reached * Return true if the StallGuard threshold has been reached
*/ */
boolean TMC26XStepper::isStallGuardOverThreshold(void) { boolean TMC26XStepper::isStallGuardOverThreshold(void) {
if (!this->started) return false; if (!this->started) return false;
@ -808,13 +808,13 @@ boolean TMC26XStepper::isStallGuardReached(void) {
return (driver_status_result & STATUS_STALL_GUARD_STATUS); return (driver_status_result & STATUS_STALL_GUARD_STATUS);
} }
//reads the stall guard setting from last status //reads the StallGuard setting from last status
//returns -1 if stallguard inforamtion is not present //returns -1 if StallGuard information is not present
int TMC26XStepper::getReadoutValue(void) { int16_t TMC26XStepper::getReadoutValue(void) {
return (int)(driver_status_result >> 10); return (int)(driver_status_result >> 10);
} }
int TMC26XStepper::getResistor() { return this->resistor; } int16_t TMC26XStepper::getResistor() { return this->resistor; }
boolean TMC26XStepper::isCurrentScalingHalfed() { boolean TMC26XStepper::isCurrentScalingHalfed() {
return !!(this->driver_configuration_register_value & VSENSE); return !!(this->driver_configuration_register_value & VSENSE);
@ -822,7 +822,7 @@ boolean TMC26XStepper::isCurrentScalingHalfed() {
/** /**
* version() returns the version of the library: * version() returns the version of the library:
*/ */
int TMC26XStepper::version(void) { return 1; } int16_t TMC26XStepper::version(void) { return 1; }
void TMC26XStepper::debugLastStatus() { void TMC26XStepper::debugLastStatus() {
#ifdef TMC_DEBUG1 #ifdef TMC_DEBUG1
@ -850,8 +850,8 @@ void TMC26XStepper::debugLastStatus() {
if (this->isStandStill()) if (this->isStandStill())
SERIAL_ECHOLNPGM("\n INFO: Motor is standing still."); SERIAL_ECHOLNPGM("\n INFO: Motor is standing still.");
unsigned long readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN; uint32_t readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN;
const int value = getReadoutValue(); const int16_t value = getReadoutValue();
if (readout_config == READ_MICROSTEP_POSTION) { if (readout_config == READ_MICROSTEP_POSTION) {
//SERIAL_PRINTF("Microstep postion phase A: "); //SERIAL_PRINTF("Microstep postion phase A: ");
SERIAL_ECHOPAIR("\n Microstep postion phase A: ", value); SERIAL_ECHOPAIR("\n Microstep postion phase A: ", value);
@ -861,7 +861,7 @@ void TMC26XStepper::debugLastStatus() {
SERIAL_ECHOPAIR("\n Stall Guard value:", value); SERIAL_ECHOPAIR("\n Stall Guard value:", value);
} }
else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) { else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) {
int stallGuard = value & 0xF, current = value & 0x1F0; int16_t stallGuard = value & 0xF, current = value & 0x1F0;
//SERIAL_PRINTF("Approx Stall Guard: "); //SERIAL_PRINTF("Approx Stall Guard: ");
SERIAL_ECHOPAIR("\n Approx Stall Guard: ", stallGuard); SERIAL_ECHOPAIR("\n Approx Stall Guard: ", stallGuard);
//SERIAL_PRINTF("Current level"); //SERIAL_PRINTF("Current level");
@ -875,11 +875,11 @@ void TMC26XStepper::debugLastStatus() {
* send register settings to the stepper driver via SPI * send register settings to the stepper driver via SPI
* returns the current status * returns the current status
*/ */
inline void TMC26XStepper::send262(unsigned long datagram) { inline void TMC26XStepper::send262(uint32_t datagram) {
unsigned long i_datagram; uint32_t i_datagram;
//preserver the previous spi mode //preserver the previous spi mode
//unsigned char oldMode = SPCR & SPI_MODE_MASK; //uint8_t oldMode = SPCR & SPI_MODE_MASK;
//if the mode is not correct set it to mode 3 //if the mode is not correct set it to mode 3
//if (oldMode != SPI_MODE3) { //if (oldMode != SPI_MODE3) {

View File

@ -83,7 +83,7 @@
* \code * \code
* TMC26XStepper stepper = TMC26XStepper(200,1,2,3,500); * TMC26XStepper stepper = TMC26XStepper(200,1,2,3,500);
* \endcode * \endcode
* see TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int rms_current) * see TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t rms_current)
* *
* Keep in mind that you need to start the driver with start() in order to get the TMC26X configured. * Keep in mind that you need to start the driver with start() in order to get the TMC26X configured.
* *
@ -122,7 +122,7 @@ class TMC26XStepper {
* You can select a different stepping with setMicrosteps() to aa different value. * You can select a different stepping with setMicrosteps() to aa different value.
* \sa start(), setMicrosteps() * \sa start(), setMicrosteps()
*/ */
TMC26XStepper(int number_of_steps, int cs_pin, int dir_pin, int step_pin, unsigned int current, unsigned int resistor=100); //resistor=150 TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150
/*! /*!
* \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode. * \brief configures and starts the TMC26X stepper driver. Before you called this function the stepper driver is in nonfunctional mode.
@ -150,13 +150,13 @@ class TMC26XStepper {
* \brief Sets the rotation speed in revolutions per minute. * \brief Sets the rotation speed in revolutions per minute.
* \param whatSpeed the desired speed in rotations per minute. * \param whatSpeed the desired speed in rotations per minute.
*/ */
void setSpeed(unsigned int whatSpeed); void setSpeed(uint16_t whatSpeed);
/*! /*!
* \brief reads out the currently selected speed in revolutions per minute. * \brief reads out the currently selected speed in revolutions per minute.
* \sa setSpeed() * \sa setSpeed()
*/ */
unsigned int getSpeed(void); uint16_t getSpeed(void);
/*! /*!
* \brief Set the number of microsteps in 2^i values (rounded) up to 256 * \brief Set the number of microsteps in 2^i values (rounded) up to 256
@ -166,7 +166,7 @@ class TMC26XStepper {
* If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2). * If you give any other value it will be rounded to the next smaller number (3 would give a microstepping of 2).
* You can always check the current microstepping with getMicrosteps(). * You can always check the current microstepping with getMicrosteps().
*/ */
void setMicrosteps(int number_of_steps); void setMicrosteps(int16_t number_of_steps);
/*! /*!
* \brief returns the effective current number of microsteps selected. * \brief returns the effective current number of microsteps selected.
@ -176,7 +176,7 @@ class TMC26XStepper {
* *
* \sa setMicrosteps() * \sa setMicrosteps()
*/ */
int getMicrosteps(void); int16_t getMicrosteps(void);
/*! /*!
* \brief Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in the other direction. * \brief Initiate a movement for the given number of steps. Positive numbers move in one, negative numbers in the other direction.
@ -193,7 +193,7 @@ class TMC26XStepper {
* You can always verify with isMoving() or even use stop() to stop the motor before giving it new step directions. * You can always verify with isMoving() or even use stop() to stop the motor before giving it new step directions.
* \sa isMoving(), getStepsLeft(), stop() * \sa isMoving(), getStepsLeft(), stop()
*/ */
char step(int number_of_steps); char step(int16_t number_of_steps);
/*! /*!
* \brief Central movement method, must be called as often as possible in the lopp function and is very fast. * \brief Central movement method, must be called as often as possible in the lopp function and is very fast.
@ -228,7 +228,7 @@ class TMC26XStepper {
* \brief Get the number of steps left in the current movement. * \brief Get the number of steps left in the current movement.
* \return The number of steps left in the movement. This number is always positive. * \return The number of steps left in the movement. This number is always positive.
*/ */
unsigned int getStepsLeft(void); uint16_t getStepsLeft(void);
/*! /*!
* \brief Stops the motor regardless if it moves or not. * \brief Stops the motor regardless if it moves or not.
@ -262,7 +262,7 @@ class TMC26XStepper {
* \sa setSpreadCycleChoper() for other alternatives. * \sa setSpreadCycleChoper() for other alternatives.
* \sa setRandomOffTime() for spreading the noise over a wider spectrum * \sa setRandomOffTime() for spreading the noise over a wider spectrum
*/ */
void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, unsigned char use_current_comparator); void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator);
/*! /*!
* \brief Sets and configures with spread cycle chopper. * \brief Sets and configures with spread cycle chopper.
@ -310,7 +310,7 @@ class TMC26XStepper {
* \param current the maximum motor current in mA * \param current the maximum motor current in mA
* \sa getCurrent(), getCurrentCurrent() * \sa getCurrent(), getCurrentCurrent()
*/ */
void setCurrent(unsigned int current); void setCurrent(uint16_t current);
/*! /*!
* \brief readout the motor maximum current in mA (1000 is an Amp) * \brief readout the motor maximum current in mA (1000 is an Amp)
@ -318,12 +318,12 @@ class TMC26XStepper {
* \return the maximum motor current in milli amps * \return the maximum motor current in milli amps
* \sa getCurrentCurrent() * \sa getCurrentCurrent()
*/ */
unsigned int getCurrent(void); uint16_t getCurrent(void);
/*! /*!
* \brief set the StallGuard threshold in order to get sensible StallGuard readings. * \brief set the StallGuard threshold in order to get sensible StallGuard readings.
* \param stall_guard_threshold -64 63 the StallGuard threshold * \param stallguard_threshold -64 63 the StallGuard threshold
* \param stall_guard_filter_enabled 0 if the filter is disabled, -1 if it is enabled * \param stallguard_filter_enabled 0 if the filter is disabled, -1 if it is enabled
* *
* The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at * The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at
* the maximum allowable load on the otor (but not before). = is a good starting point (and the default) * the maximum allowable load on the otor (but not before). = is a good starting point (and the default)
@ -335,7 +335,7 @@ class TMC26XStepper {
* *
* \sa getCurrentStallGuardReading() to read out the current value. * \sa getCurrentStallGuardReading() to read out the current value.
*/ */
void setStallGuardThreshold(char stall_guard_threshold, char stall_guard_filter_enabled); void setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled);
/*! /*!
* \brief reads out the StallGuard threshold * \brief reads out the StallGuard threshold
@ -366,8 +366,8 @@ class TMC26XStepper {
* (1/2 or 1/4th otf the configured current). * (1/2 or 1/4th otf the configured current).
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/ */
void setCoolStepConfiguration(unsigned int lower_SG_threshold, unsigned int SG_hysteresis, unsigned char current_decrement_step_size, void setCoolStepConfiguration(uint16_t lower_SG_threshold, uint16_t SG_hysteresis, uint8_t current_decrement_step_size,
unsigned char current_increment_step_size, unsigned char lower_current_limit); uint8_t current_increment_step_size, uint8_t lower_current_limit);
/*! /*!
* \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it. * \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it.
@ -387,32 +387,32 @@ class TMC26XStepper {
* \brief returns the lower StallGuard threshold for the CoolStep operation * \brief returns the lower StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
*/ */
unsigned int getCoolStepLowerSgThreshold(); uint16_t getCoolStepLowerSgThreshold();
/*! /*!
* \brief returns the upper StallGuard threshold for the CoolStep operation * \brief returns the upper StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
*/ */
unsigned int getCoolStepUpperSgThreshold(); uint16_t getCoolStepUpperSgThreshold();
/*! /*!
* \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current. * \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current.
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
*/ */
unsigned char getCoolStepNumberOfSGReadings(); uint8_t getCoolStepNumberOfSGReadings();
/*! /*!
* \brief returns the increment steps for the current for the CoolStep operation * \brief returns the increment steps for the current for the CoolStep operation
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
*/ */
unsigned char getCoolStepCurrentIncrementSize(); uint8_t getCoolStepCurrentIncrementSize();
/*! /*!
* \brief returns the absolut minium current for the CoolStep operation * \brief returns the absolut minium current for the CoolStep operation
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/ */
unsigned char getCoolStepLowerCurrentLimit(); uint8_t getCoolStepLowerCurrentLimit();
/*! /*!
* \brief Get the current microstep position for phase A * \brief Get the current microstep position for phase A
@ -420,7 +420,7 @@ class TMC26XStepper {
* *
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
*/ */
int getMotorPosition(void); int16_t getMotorPosition(void);
/*! /*!
* \brief Reads the current StallGuard value. * \brief Reads the current StallGuard value.
@ -428,14 +428,14 @@ class TMC26XStepper {
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time. * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges. * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/ */
int getCurrentStallGuardReading(void); int16_t getCurrentStallGuardReading(void);
/*! /*!
* \brief Reads the current current setting value as fraction of the maximum current * \brief Reads the current current setting value as fraction of the maximum current
* Returns values between 0 and 31, representing 1/32 to 32/32 (=1) * Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
* \sa setCoolStepConfiguration() * \sa setCoolStepConfiguration()
*/ */
unsigned char getCurrentCSReading(void); uint8_t getCurrentCSReading(void);
/*! /*!
@ -451,7 +451,7 @@ class TMC26XStepper {
* may not be the fastest. * may not be the fastest.
* \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent() * \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
*/ */
unsigned int getCurrentCurrent(void); uint16_t getCurrentCurrent(void);
/*! /*!
* \brief checks if there is a StallGuard warning in the last status * \brief checks if there is a StallGuard warning in the last status
@ -552,56 +552,54 @@ class TMC26XStepper {
* \brief Returns the current sense resistor value in milliohm. * \brief Returns the current sense resistor value in milliohm.
* The default value of ,15 Ohm will return 150. * The default value of ,15 Ohm will return 150.
*/ */
int getResistor(); int16_t getResistor();
/*! /*!
* \brief Prints out all the information that can be found in the last status read out - it does not force a status readout. * \brief Prints out all the information that can be found in the last status read out - it does not force a status readout.
* The result is printed via Serial * The result is printed via Serial
*/ */
void debugLastStatus(void); void debugLastStatus(void);
/*! /*!
* \brief library version * \brief library version
* \return the version number as int. * \return the version number as int.
*/ */
int version(void); int16_t version(void);
private: private:
unsigned int steps_left; // The steps the motor has to do to complete the movement uint16_t steps_left; // The steps the motor has to do to complete the movement
int direction; // Direction of rotation int16_t direction; // Direction of rotation
unsigned long step_delay; // Delay between steps, in ms, based on speed uint32_t step_delay; // Delay between steps, in ms, based on speed
int number_of_steps; // Total number of steps this motor can take int16_t number_of_steps; // Total number of steps this motor can take
unsigned int speed; // Store the current speed in order to change the speed after changing microstepping uint16_t speed; // Store the current speed in order to change the speed after changing microstepping
unsigned int resistor; // Current sense resitor value in milliohm uint16_t resistor; // Current sense resitor value in milliohm
unsigned long last_step_time; // Time stamp in ms of when the last step was taken uint32_t last_step_time, // Timestamp (ms) of the last step
unsigned long next_step_time; // Time stamp in ms of when the last step was taken next_step_time; // Timestamp (ms) of the next step
// Driver control register copies to easily set & modify the registers // Driver control register copies to easily set & modify the registers
unsigned long driver_control_register_value; uint32_t driver_control_register_value,
unsigned long chopper_config_register; chopper_config_register,
unsigned long cool_step_register_value; cool_step_register_value,
unsigned long stall_guard2_current_register_value; stallguard2_current_register_value,
unsigned long driver_configuration_register_value; driver_configuration_register_value,
// The driver status result driver_status_result; // The driver status result
unsigned long driver_status_result;
// Helper routione to get the top 10 bit of the readout // Helper routione to get the top 10 bit of the readout
inline int getReadoutValue(); inline int16_t getReadoutValue();
// The pins for the stepper driver // The pins for the stepper driver
unsigned char cs_pin; uint8_t cs_pin, step_pin, dir_pin;
unsigned char step_pin;
unsigned char dir_pin;
// Status values // Status values
boolean started; // If the stepper has been started yet boolean started; // If the stepper has been started yet
int microsteps; // The current number of micro steps int16_t microsteps; // The current number of micro steps
char constant_off_time; // We need to remember this value in order to enable and disable the motor char constant_off_time; // We need to remember this value in order to enable and disable the motor
unsigned char cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature uint8_t cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature
boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled
// SPI sender // SPI sender
inline void send262(unsigned long datagram); inline void send262(uint32_t datagram);
}; };
#endif // _TMC26XSTEPPER_H_ #endif // _TMC26XSTEPPER_H_