diff --git a/firmware/stepper_nano_zero/A4954.cpp b/firmware/stepper_nano_zero/A4954.cpp index ef9f9e6..c10a0a3 100644 --- a/firmware/stepper_nano_zero/A4954.cpp +++ b/firmware/stepper_nano_zero/A4954.cpp @@ -316,6 +316,7 @@ int32_t A4954::move(int32_t stepAngle, uint32_t mA) setDAC(0,0); //turn current off bridge1(3); //tri state bridge outputs bridge2(3); //tri state bridge outputs + return stepAngle; } //WARNING("move %d %d",stepAngle,mA); diff --git a/firmware/stepper_nano_zero/Flash.cpp b/firmware/stepper_nano_zero/Flash.cpp index 5b8d6be..faaa287 100644 --- a/firmware/stepper_nano_zero/Flash.cpp +++ b/firmware/stepper_nano_zero/Flash.cpp @@ -71,7 +71,7 @@ void flashWrite(const volatile void *flash_ptr,const void *data, uint32_t size) destPtr=(uint8_t *)flash_ptr; srcPtr=(uint8_t *)data; - //LOG("flash write called"); + LOG("flash write called"); while(size>0) { uint32_t i,j; @@ -80,11 +80,11 @@ void flashWrite(const volatile void *flash_ptr,const void *data, uint32_t size) offset=((uint32_t)destPtr)%(FLASH_ROW_SIZE); //offset into page bytesInBlock=FLASH_ROW_SIZE-offset; //this is how many bytes we need to overwrite in this page - //LOG("offset %d, bytesInBlock %d size %d", offset, bytesInBlock,size); + LOG("offset %d, bytesInBlock %d size %d", offset, bytesInBlock,size); //get pointer to start of page ptrPage=(uint32_t *) ((((uint32_t)destPtr)/(FLASH_ROW_SIZE)) * FLASH_ROW_SIZE); - //LOG("pointer to page %d(0x%08x) %d",(uint32_t)ptrPage,(uint32_t)ptrPage,destPtr); + LOG("pointer to page %d(0x%08x) %d",(uint32_t)ptrPage,(uint32_t)ptrPage,destPtr); //fill page buffer with data from flash memcpy(buffer,ptrPage,FLASH_ROW_SIZE); @@ -95,7 +95,7 @@ void flashWrite(const volatile void *flash_ptr,const void *data, uint32_t size) { i=size; } - //LOG("changing %d bytes",i); + LOG("changing %d bytes",i); memcpy(&buffer[offset],srcPtr,i); //erase page diff --git a/firmware/stepper_nano_zero/board.h b/firmware/stepper_nano_zero/board.h index 4c7287e..fa0d095 100644 --- a/firmware/stepper_nano_zero/board.h +++ b/firmware/stepper_nano_zero/board.h @@ -39,18 +39,28 @@ #define NZS_LCD_ABSOULTE_ANGLE //define this to show angle from zero in positive and negative direction - // for example 2 rotations from start will be angle of 720 degrees +// for example 2 rotations from start will be angle of 720 degrees //#define ENABLE_PHASE_PREDICTION //this enables prediction of phase at high velocity to increase motor speed - //as of FW0.11 it is considered development only +//as of FW0.11 it is considered development only -#define VERSION "FW: 0.25" //this is what prints on LCD during splash screen +#define VERSION "FW: 0.28" //this is what prints on LCD during splash screen //Define this to allow command out serial port, else hardware serial is debug log -#define CMD_SERIAL_PORT +//#define CMD_SERIAL_PORT #define SERIAL_BAUD (115200) //baud rate for the serial ports +//This section is for using the step and dir pins as serial port +// when the enable pin is inactive. +#define USE_STEP_DIR_SERIAL +#define STEP_DIR_BAUD (19200) //this is the baud rate we will use + +// These are used as an attempt to use TC4 to count steps +// currently this is not working. +//#define USE_NEW_STEP //define this to use new step method +//#define USE_TC_STEP //use timer counter for step pin + #ifndef F_CPU #define F_CPU (48000000UL) #endif @@ -122,7 +132,10 @@ * 0.23 -- added motor voltage sense to remove stepping on power up * 0.24 - Disabled the home command which used the enable pin if you do not have enable pin * 0.25 - Added pin read command - * + * 0.26 - changed the step/dir pins to be input_pullups + * 0.27 - added the option to make the step/dir uart when enable is low. + * - fixed enable to line to disable the A4954 driver + * 0.28 - Enabled some homing options (still under development) */ @@ -150,6 +163,8 @@ typedef enum { CTRL_POS_VELOCITY_PID =4, //PID Velocity controller } feedbackCtrl_t; +// ******** EVENT SYS USAGAE ************ +// Channel 0 - Step pin event // ******** TIMER USAGE A4954 versions ************ //TCC1 is used for DAC PWM to the A4954 @@ -157,12 +172,14 @@ typedef enum { //D0 step input could use TCC1 or TCC0 if not used //TC5 is use for timing the control loop //TC3 is used for planner tick +//TC4 is used for step count // ******** TIMER USAGE NEMA23 10A versions ************ //TCC0 PWM for the FET IN pins //D10 step input could use TC3 or TCC0 if not used //TC5 is use for timing the control loop //TC3 is used for planner tick +//TC4 is used for step count @@ -183,6 +200,10 @@ typedef enum { #define PIN_MISO (22) #ifdef MECHADUINO_HARDWARE +#ifdef USE_STEP_DIR_SERIAL +#error "Step/Dir UART not supported on Mechaduino yet" +#endif + #define PIN_ERROR (19) //analogInputToDigitalPin(PIN_A5)) #else //not Mechaduino hardware #ifdef NEMA17_SMART_STEPPER_3_21_2017 @@ -295,8 +316,8 @@ static void boardSetupPins(void) pinMode(PIN_SW4, INPUT_PULLUP); #endif - pinMode(PIN_STEP_INPUT, INPUT); - pinMode(PIN_DIR_INPUT, INPUT); + pinMode(PIN_STEP_INPUT, INPUT_PULLUP); + pinMode(PIN_DIR_INPUT, INPUT_PULLUP); #ifdef PIN_ENABLE pinMode(PIN_ENABLE, INPUT_PULLUP); //default error pin as enable pin with pull up @@ -377,28 +398,95 @@ static void inline RED_LED(bool state) #define NVIC_IS_IRQ_ENABLED(x) (NVIC->ISER[0] & (1 << ((uint32_t)(x) & 0x1F)))!=0 +static inline uint8_t getPinMux(uint16_t ulPin) +{ + uint8_t temp; + if ((ulPin & 0x01)==0) + { + temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ; + }else + { + temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg)>>4 & 0xF; + } + return temp; +} + + +static inline uint8_t getPinCfg(uint16_t ulPin) +{ + uint8_t temp; + + temp = PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg; + return temp; +} + +static inline void setPinCfg(uint16_t ulPin, uint8_t val) +{ + PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg=val; +} + + + +static inline void setPinMux(uint16_t ulPin, uint8_t val) +{ + uint8_t temp; + temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg); + if ((ulPin & 0x01)==0) + { + //if an even pin + temp = (temp & 0xF0) | (val & 0x0F); + }else + { + temp = (temp & 0x0F) | ((val<<4) & 0x0F); + } + PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg=temp; + PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; // Enable port mux +} static inline void SET_PIN_PERHERIAL(uint16_t ulPin,EPioType ulPeripheral) { - if ( g_APinDescription[ulPin].ulPin & 1 ) // is pin odd? - { - uint32_t temp ; - - // Get whole current setup for both odd and even pins and remove odd one - temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ; - // Set new muxing - PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXO( ulPeripheral ) ; - // Enable port mux - PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; - } - else // even pin - { - uint32_t temp ; - - temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXO( 0xF ) ; - PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXE( ulPeripheral ) ; - PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; // Enable port mux - } + if ( g_APinDescription[ulPin].ulPin & 1 ) // is pin odd? + { + uint32_t temp ; + + // Get whole current setup for both odd and even pins and remove odd one + temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ; + // Set new muxing + PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXO( ulPeripheral ) ; + // Enable port mux + PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; + } + else // even pin + { + uint32_t temp ; + + temp = (PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg) & PORT_PMUX_PMUXO( 0xF ) ; + PORT->Group[g_APinDescription[ulPin].ulPort].PMUX[g_APinDescription[ulPin].ulPin >> 1].reg = temp|PORT_PMUX_PMUXE( ulPeripheral ) ; + PORT->Group[g_APinDescription[ulPin].ulPort].PINCFG[g_APinDescription[ulPin].ulPin].reg |= PORT_PINCFG_PMUXEN ; // Enable port mux + } +} + + +//the Arduino delay function requires interrupts to work. +// if interrupts are disabled use the delayMicroseconds which is a spin loop +static inline void DelayMs(uint32_t ms) +{ + uint32_t prim; + /* Read PRIMASK register, check interrupt status before you disable them */ + /* Returns 0 if they are enabled, or non-zero if disabled */ + prim = __get_PRIMASK(); + + if (prim==0) + { + delay(ms); + }else + { + while(ms) + { + delayMicroseconds(1000); + ms--; + } + } } #endif//__BOARD_H__ diff --git a/firmware/stepper_nano_zero/commands.cpp b/firmware/stepper_nano_zero/commands.cpp index 6b7499d..be9892a 100644 --- a/firmware/stepper_nano_zero/commands.cpp +++ b/firmware/stepper_nano_zero/commands.cpp @@ -4,7 +4,7 @@ #include "stepper_controller.h" #include #include "nonvolatile.h" -#include "Reset.h" +#include "reset.h" #include "nzs.h" #include "ftoa.h" #include "board.h" @@ -15,6 +15,7 @@ extern int32_t dataEnabled; #define COMMANDS_PROMPT (":>") sCmdUart UsbUart; sCmdUart SerialUart; +sCmdUart HostUart; //uart on the step/dir pins static int isPowerOfTwo (unsigned int x) { @@ -52,6 +53,7 @@ CMD_STR(errorlimit, "gets/set the error limit which will assert error pin (when CMD_STR(ctrlmode, "gets/set the feedback controller mode of operation"); CMD_STR(maxcurrent, "gets/set the maximum motor current allowed in milliAmps"); CMD_STR(holdcurrent, "gets/set the motor holding current in milliAmps, only used in the simple positional PID mode"); +CMD_STR(homecurrent, "gets/set the motor moving and holding currents that will be used when pin A3 is low"); CMD_STR(motorwiring, "gets/set the motor wiring direction, should only be used by experts"); CMD_STR(stepsperrotation, "gets/set the motor steps per rotation, should only be used by experts"); @@ -71,12 +73,15 @@ CMD_STR(eepromloc, "returns location in degreees eeprom on power up"); CMD_STR(eepromwrite, "forces write of location to eeprom"); CMD_STR(eepromsetloc, "sets the device angle based on EEPROM last reading, compenstates for error") CMD_STR(setpos, "sets the current angle in degrees"); -CMD_STR(reboot, "reboots the unit") +CMD_STR(reboot, "reboots the unit"); +CMD_STR(homepin, "sets the pin used to drop to homing current"); +CMD_STR(homeangledelay, "sets the angle delay in dropping to homing current"); #ifdef PIN_ENABLE CMD_STR(home, "moves the motor until home switch (enable pin) is pulled low. example 'home 360 0.5' move up to 360 degrees at 0.5 RPM ") #endif CMD_STR(pinread, "reads pins as binary (bit 0-step, bit 1 - Dir, bit 2 - Enable, bit 3 - Error, bit 4 - A3, bit 5- TX, bit 6 - RX") - +CMD_STR(errorpin, "Sets the logic level of error pin") +CMD_STR(geterror, "gets current error") //List of supported commands sCommand Cmds[] = { @@ -104,6 +109,7 @@ sCommand Cmds[] = COMMAND(ctrlmode), COMMAND(maxcurrent), COMMAND(holdcurrent), + COMMAND(homecurrent), COMMAND(motorwiring), COMMAND(stepsperrotation), @@ -124,13 +130,47 @@ sCommand Cmds[] = COMMAND(setpos), COMMAND(reboot), COMMAND(eepromsetloc), + COMMAND(homepin), + COMMAND(homeangledelay), #ifdef PIN_ENABLE COMMAND(home), #endif COMMAND(pinread), + COMMAND(errorpin), + COMMAND(geterror), {"",0,""}, //End of list signal }; +static int geterror_cmd(sCmdUart *ptrUart,int argc, char * argv[]) +{ + float f; + char str[30]; + f=ANGLE_T0_DEGREES(stepperCtrl.getLoopError()); + ftoa(f,str,2,'f'); + CommandPrintf(ptrUart,"error %s deg",str); + return 0; +} + + +static int errorpin_cmd(sCmdUart *ptrUart,int argc, char * argv[]) +{ + if (argc==1) + { + + SystemParams_t params; + + memcpy(¶ms,&NVM->SystemParams, sizeof(SystemParams_t) ); + params.errorLogic=atol(argv[0]); + + nvmWriteSystemParms(params); + stepperCtrl.updateParamsFromNVM(); + + } + CommandPrintf(ptrUart,"error pin assert level is %d\n\r",NVM->SystemParams.errorLogic); + return 0; + +} + static int pinread_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { uint8_t ret=0; @@ -153,7 +193,7 @@ static int pinread_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { ret |= 0x08; } - if (digitalRead(analogInputToDigitalPin(PIN_A3))) + if (digitalRead(PIN_A3)) { ret |= 0x10; } @@ -165,7 +205,7 @@ static int pinread_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { ret |= 0x40; } - CommandPrintf(ptrUart,"%02X\n\r",ret); + CommandPrintf(ptrUart,"0x%02X\n\r",ret); return 0; } @@ -175,6 +215,9 @@ static void errorPinISR(void) SmartPlanner.stop(); //stop the planner } + + + static int home_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { float rpm=1; @@ -416,6 +459,123 @@ static int motorwiring_cmd(sCmdUart *ptrUart,int argc, char * argv[]) return 1; } + +static int homeangledelay_cmd(sCmdUart *ptrUart,int argc, char * argv[]) +{ + float f; + char str[30]; + + if (argc == 1) + { + f=atof(argv[0]); + + SystemParams_t params; + + memcpy(¶ms,&NVM->SystemParams, sizeof(SystemParams_t) ); + params.homeAngleDelay=ANGLE_FROM_DEGREES(f); + + nvmWriteSystemParms(params); + stepperCtrl.updateParamsFromNVM(); + + } + + f=ANGLE_T0_DEGREES(NVM->SystemParams.homeAngleDelay); + ftoa(f,str,2,'f'); + CommandPrintf(ptrUart,"home angle delay %s\n\r",str); + return 0; +} + +static int homepin_cmd(sCmdUart *ptrUart,int argc, char * argv[]) +{ + int32_t x; + if (argc == 0) + { + x=NVM->SystemParams.homePin; + CommandPrintf(ptrUart,"home pin %d\n\r",x); + return 0; + } + + if (argc == 1) + { + x=atol(argv[0]); + + SystemParams_t params; + + memcpy(¶ms,&NVM->SystemParams, sizeof(SystemParams_t) ); + params.homePin=x; + + nvmWriteSystemParms(params); + stepperCtrl.updateParamsFromNVM(); + + + x=NVM->SystemParams.homePin; + CommandPrintf(ptrUart,"home pin %d\n\r",x); + return 0; + + } + + CommandPrintf(ptrUart, "use 'sethomepin 17' to set maximum home pin to A3"); + + return 1; +} + + +static int homecurrent_cmd(sCmdUart *ptrUart,int argc, char * argv[]) +{ + uint32_t x,y; + if (argc == 0) + { + x=NVM->motorParams.homeMa; + y=NVM->motorParams.homeHoldMa; + CommandPrintf(ptrUart,"current %umA, %umA\n\r",x,y); + return 0; + } + + if (argc == 1) + { + x=atol(argv[0]); + + MotorParams_t motorParams; + + memcpy(&motorParams,&NVM->motorParams, sizeof(motorParams) ); + motorParams.homeMa=x; + + nvmWriteMotorParms(motorParams); + stepperCtrl.updateParamsFromNVM(); + + + x=NVM->motorParams.homeMa; + y=NVM->motorParams.homeHoldMa; + CommandPrintf(ptrUart,"current %umA, %umA\n\r",x,y); + return 0; + + } + if (argc == 2) + { + x=atol(argv[0]); + y=atol(argv[1]); + + MotorParams_t motorParams; + + memcpy(&motorParams,&NVM->motorParams, sizeof(motorParams) ); + motorParams.homeMa=x; + motorParams.homeHoldMa=y; + + nvmWriteMotorParms(motorParams); + stepperCtrl.updateParamsFromNVM(); + + + x=NVM->motorParams.homeMa; + y=NVM->motorParams.homeHoldMa; + CommandPrintf(ptrUart,"current %umA, %umA\n\r",x,y); + return 0; + + } + CommandPrintf(ptrUart, "use 'homecurrent 1000 500' to set maximum home current to 1.0A and hold to 500ma"); + + return 1; +} + static int holdcurrent_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { @@ -492,6 +652,7 @@ static int maxcurrent_cmd(sCmdUart *ptrUart,int argc, char * argv[]) } + static int ctrlmode_cmd(sCmdUart *ptrUart,int argc, char * argv[]) { bool ret; @@ -1309,10 +1470,29 @@ uint8_t putch_hw(char data) return Serial5.write((uint8_t)data); } + +uint8_t kbhit_step_dir(void) +{ + return Serial1.available(); + //return SerialUSB.peek() != -1; +} +uint8_t getChar_step_dir(void) +{ + return Serial1.read(); +} +uint8_t putch_step_dir(char data) +{ + return Serial1.write((uint8_t)data); +} + + + void commandsInit(void) { CommandInit(&UsbUart, kbhit, getChar, putch ,NULL); //set up the UART structure + CommandInit(&HostUart, kbhit_step_dir, getChar_step_dir, putch_step_dir ,NULL); //set up the UART structure for step and dir pins + #ifdef CMD_SERIAL_PORT CommandInit(&SerialUart, kbhit_hw, getChar_hw, putch_hw ,NULL); //set up the UART structure Serial5.print("\n\rPower Up\n\r"); @@ -1325,6 +1505,17 @@ void commandsInit(void) int commandsProcess(void) { +#ifdef USE_STEP_DIR_SERIAL + //if the step pin is configured to the SerialCom 0 then we need to process commands + //if PA11 (D0) is configured to perpherial C then the step pin is UART + if (getPinMux(PIN_STEP_INPUT) == PORT_PMUX_PMUXE_C_Val) + { + //SerialUSB.println("host"); + CommandProcess(&HostUart,Cmds,' ',COMMANDS_PROMPT); + } +#endif //USE_STEP_DIR_SERIAL + + #ifdef CMD_SERIAL_PORT CommandProcess(&SerialUart,Cmds,' ',COMMANDS_PROMPT); #endif diff --git a/firmware/stepper_nano_zero/nonvolatile.cpp b/firmware/stepper_nano_zero/nonvolatile.cpp index 8336b2a..09cd9d2 100644 --- a/firmware/stepper_nano_zero/nonvolatile.cpp +++ b/firmware/stepper_nano_zero/nonvolatile.cpp @@ -20,12 +20,12 @@ // be sure to set the last word as status flag // this save time calibrating each time we do a code build #ifdef NZS_FAST_CAL -__attribute__((__aligned__(FLASH_ROW_SIZE))) const uint16_t NVM_flash[16640]={ //allocates 33280 bytes +__attribute__((__aligned__(FLASH_ROW_SIZE))) const uint16_t NVM_flash[16767]={ //allocates 33280 bytes #else __attribute__((__aligned__(FLASH_ROW_SIZE))) const uint16_t NVM_flash[256]={ //allocates 512 bytes #endif //insert the getcal command calibration data here - 0xFFFF + 0xFFFF }; diff --git a/firmware/stepper_nano_zero/nonvolatile.h b/firmware/stepper_nano_zero/nonvolatile.h index 30e5da0..14aa1a4 100644 --- a/firmware/stepper_nano_zero/nonvolatile.h +++ b/firmware/stepper_nano_zero/nonvolatile.h @@ -26,6 +26,8 @@ typedef struct { typedef struct { int32_t currentMa; //maximum current for the motor int32_t currentHoldMa; //hold current for the motor + int32_t homeMa; //maximum current when error homing + int32_t homeHoldMa; //hold current when error homing bool motorWiring; //forward wiring of motor or reverse int32_t fullStepsPerRotation; //how many full steps per rotation is the motor bool parametersVaild; @@ -37,6 +39,9 @@ typedef struct { int32_t errorLimit; //error limit before error pin asserts 65536==360degrees ErrorPinMode_t errorPinMode; //is error pin used for enable, error, or bidirectional feedbackCtrl_t controllerMode; //feedback mode for the controller + int32_t homePin; //if greater than zero this is the pin we use trigger home current settings + bool errorLogic; //if high and error will be high on output pin + int32_t homeAngleDelay; //the angle to delay before switching to lower homing current bool parametersVaild; } SystemParams_t; @@ -60,7 +65,7 @@ typedef struct { } nvm_t; #ifdef NZS_FAST_CAL -extern const uint16_t NVM_flash[16640]; +extern const uint16_t NVM_flash[16767]; #else extern const uint16_t NVM_flash[256]; #endif diff --git a/firmware/stepper_nano_zero/nzs.cpp b/firmware/stepper_nano_zero/nzs.cpp index 7e25705..8f719cc 100644 --- a/firmware/stepper_nano_zero/nzs.cpp +++ b/firmware/stepper_nano_zero/nzs.cpp @@ -18,6 +18,7 @@ #include "nonvolatile.h" #include "angle.h" #include "eeprom.h" +#include "steppin.h" #pragma GCC push_options #pragma GCC optimize ("-Ofast") @@ -371,24 +372,13 @@ static menuItem_t MenuCal[] { -//this function is called on the rising edge of a step from external device -static void stepInput(void) -{ - static int dir; - //read our direction pin - dir = digitalRead(PIN_DIR_INPUT); - if (CW_ROTATION == NVM->SystemParams.dirPinRotation) - { - dir=!dir; //reverse the rotation - } - stepperCtrl.requestStep(dir,1); -} //this function is called when error pin changes as enable signal static void enableInput(void) { + static bool lastState=true; #ifdef PIN_ENABLE if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ENABLE) { @@ -406,7 +396,6 @@ static void enableInput(void) enableState=enable; //stepperCtrl.enable(enable); } - #else if (NVM->SystemParams.errorPinMode == ERROR_PIN_MODE_ENABLE) { @@ -425,6 +414,61 @@ static void enableInput(void) //stepperCtrl.enable(enable); } #endif + +#ifdef USE_STEP_DIR_SERIAL + + static uint8_t pinCFG[2]; + static uint8_t pinMux[2]; + if (enableState == false && lastState==true) + { + // turn the step/dir to serial port + + //save pin config for restoring + pinCFG[0]=getPinCfg(PIN_STEP_INPUT); + pinCFG[1]=getPinCfg(PIN_DIR_INPUT); + pinMux[0]=getPinMux(PIN_STEP_INPUT); + pinMux[1]=getPinMux(PIN_DIR_INPUT); + + //lets see if the step pin has interrupt enabled + if (pinMux[0] == PORT_PMUX_PMUXE_A_Val) + { + EExt_Interrupts in = g_APinDescription[PIN_STEP_INPUT].ulExtInt; + EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT(1 << in); //disable the interrupt + //we need to disable the interrupt + } + + //now we need to set the pins to serial port peripheral (sercom0) + setPinMux(PIN_STEP_INPUT,PORT_PMUX_PMUXE_C_Val); + setPinMux(PIN_DIR_INPUT,PORT_PMUX_PMUXE_C_Val); + + //make sure that step pin is input with mux to peripheral + setPinCfg(PIN_STEP_INPUT, PORT_PINCFG_PMUXEN | PORT_PINCFG_INEN | PORT_PINCFG_PULLEN); + + //make sure that dir pin is an output with mux to peripheral + setPinCfg(PIN_DIR_INPUT, PORT_PINCFG_PMUXEN ); + + Serial1.begin(STEP_DIR_BAUD); + + } + if (enableState == true && lastState==false) + { + Serial1.end(); + setPinMux(PIN_STEP_INPUT,pinMux[0]); + setPinMux(PIN_DIR_INPUT,pinMux[1]); + setPinCfg(PIN_STEP_INPUT,pinCFG[0]); + setPinCfg(PIN_DIR_INPUT,pinCFG[1]); + //turn step/dir pins back to GPIO + if (PORT_PMUX_PMUXE_A_Val == pinMux[0]) + { + //if interrupt was enabled for step pin renable it. + EExt_Interrupts in = g_APinDescription[PIN_STEP_INPUT].ulExtInt; + EIC->INTENSET.reg = EIC_INTENCLR_EXTINT(1 << in); //enable the interrupt + } + + } + +#endif //USE_STEP_DIR_SERIAL + lastState=enableState; } @@ -441,12 +485,14 @@ void TC5_Handler() YELLOW_LED(error); #ifdef PIN_ENABLE GPIO_OUTPUT(PIN_ERROR); + bool level; + level = !NVM->SystemParams.errorLogic; if (error) { //assume high is inactive and low is active on error pin - digitalWrite(PIN_ERROR,LOW); + digitalWrite(PIN_ERROR,level); }else { - digitalWrite(PIN_ERROR,HIGH); + digitalWrite(PIN_ERROR,!level); } #else @@ -494,6 +540,9 @@ void validateAndInitNVMParams(void) params.dirPinRotation=CW_ROTATION; //default to clockwise rotation when dir is high params.errorLimit=(int32_t)ANGLE_FROM_DEGREES(1.8); params.errorPinMode=ERROR_PIN_MODE_ENABLE; //default to enable pin + params.homePin=-1; + params.errorLogic=false; + params.homeAngleDelay=ANGLE_FROM_DEGREES(10); nvmWriteSystemParms(params); } @@ -672,7 +721,7 @@ void NZS::begin(void) Lcd.setMenu(MenuMain); #endif - attachInterrupt(digitalPinToInterrupt(PIN_STEP_INPUT), stepInput, RISING); + stepPinSetup(); //setup the step pin #ifdef PIN_ENABLE attachInterrupt(digitalPinToInterrupt(PIN_ENABLE), enableInput, CHANGE); diff --git a/firmware/stepper_nano_zero/stepper_controller.cpp b/firmware/stepper_nano_zero/stepper_controller.cpp index 8beb92c..d013db9 100644 --- a/firmware/stepper_nano_zero/stepper_controller.cpp +++ b/firmware/stepper_nano_zero/stepper_controller.cpp @@ -14,6 +14,7 @@ #include "nonvolatile.h" //for programmable parameters #include #include +#include "steppin.h" #pragma GCC push_options #pragma GCC optimize ("-Ofast") @@ -116,6 +117,8 @@ void StepperCtrl::updateParamsFromNVM(void) if (NVM->SystemParams.parametersVaild) { memcpy((void *)&systemParams, (void *)&NVM->SystemParams, sizeof(systemParams)); + LOG("Home pin %d",systemParams.homePin); + }else { ERROR("This should never happen but just in case"); @@ -124,6 +127,9 @@ void StepperCtrl::updateParamsFromNVM(void) systemParams.dirPinRotation=CW_ROTATION; //default to clockwise rotation when dir is high systemParams.errorLimit=(int32_t)ANGLE_FROM_DEGREES(1.8); systemParams.errorPinMode=ERROR_PIN_MODE_ENABLE; //default to enable pin + systemParams.errorLogic=false; + systemParams.homeAngleDelay=ANGLE_FROM_DEGREES(10); + systemParams.homePin=-1; //no homing pin configured } //default the error pin to input, if it is an error pin the @@ -142,6 +148,8 @@ void StepperCtrl::updateParamsFromNVM(void) motorParams.fullStepsPerRotation=200; motorParams.currentHoldMa=500; motorParams.currentMa=1500; + motorParams.homeHoldMa=200; + motorParams.homeMa=800; motorParams.motorWiring=true; //memcpy((void *)&Params, (void *)&motorParams, sizeof(motorParams)); //nvmWriteMotorParms(Params); @@ -198,19 +206,19 @@ void StepperCtrl::setLocationFromEncoder(void) //our cal table starts at angle zero, so lets set starting based on this and stepsize LOG("start angle %d, encoder %d", (uint16_t)a,x); -// we were rounding to nearest full step, but this should not be needed TBS 10/12/2017 -// //TODO we need to handle 0.9 degree motor -// if (CALIBRATION_TABLE_SIZE == motorParams.fullStepsPerRotation) -// { -// n=(int32_t)ANGLE_STEPS/CALIBRATION_TABLE_SIZE; -// -// calIndex=((int32_t)((uint16_t)a+n/2)*CALIBRATION_TABLE_SIZE)/ANGLE_STEPS; //find calibration index -// if (calIndex>CALIBRATION_TABLE_SIZE) -// { -// calIndex-=CALIBRATION_TABLE_SIZE; -// } -// a=(uint16_t)((calIndex*ANGLE_STEPS)/CALIBRATION_TABLE_SIZE); -// } + // we were rounding to nearest full step, but this should not be needed TBS 10/12/2017 + // //TODO we need to handle 0.9 degree motor + // if (CALIBRATION_TABLE_SIZE == motorParams.fullStepsPerRotation) + // { + // n=(int32_t)ANGLE_STEPS/CALIBRATION_TABLE_SIZE; + // + // calIndex=((int32_t)((uint16_t)a+n/2)*CALIBRATION_TABLE_SIZE)/ANGLE_STEPS; //find calibration index + // if (calIndex>CALIBRATION_TABLE_SIZE) + // { + // calIndex-=CALIBRATION_TABLE_SIZE; + // } + // a=(uint16_t)((calIndex*ANGLE_STEPS)/CALIBRATION_TABLE_SIZE); + // } x=(int32_t)((((float)(uint16_t)a)*360.0/(float)ANGLE_STEPS)*1000); @@ -660,6 +668,8 @@ stepCtrlError_t StepperCtrl::begin(void) LOG("motorWiring %d", motorParams.motorWiring); LOG("currentMa %d", motorParams.currentMa); LOG("holdCurrentMa %d", motorParams.currentHoldMa); + LOG("homeMa %d", motorParams.homeMa); + LOG("homeHoldMa %d", motorParams.homeHoldMa); updateParamsFromNVM(); //update the local cache from the NVM @@ -1045,6 +1055,7 @@ bool StepperCtrl::pidFeedback(int64_t desiredLoc, int64_t currentLoc, Control_t static int32_t maxError=0; static int32_t lastError=0; static int32_t Iterm=0; + int32_t ma; int64_t y; int32_t fullStep=ANGLE_STEPS/motorParams.fullStepsPerRotation; @@ -1065,25 +1076,34 @@ bool StepperCtrl::pidFeedback(int64_t desiredLoc, int64_t currentLoc, Control_t Iterm+=(pPID.Ki * error); + if (systemParams.homePin>0 && digitalRead(systemParams.homePin)==0) + { + ma=motorParams.homeMa; + } else + { + ma=motorParams.currentMa; + } + //Over the long term we do not want error // to be much more than our threshold - if (Iterm> (motorParams.currentMa*CTRL_PID_SCALING) ) + if (Iterm> (ma*CTRL_PID_SCALING) ) { - Iterm=(motorParams.currentMa*CTRL_PID_SCALING) ; + Iterm=(ma*CTRL_PID_SCALING) ; } - if (Iterm<-(motorParams.currentMa*CTRL_PID_SCALING) ) + if (Iterm<-(ma*CTRL_PID_SCALING) ) { - Iterm=-(motorParams.currentMa*CTRL_PID_SCALING) ; + Iterm=-(ma*CTRL_PID_SCALING) ; } u=((pPID.Kp * error) + Iterm - (pPID.Kd *(lastError-error))); U=abs(u)/CTRL_PID_SCALING; - if (U>motorParams.currentMa) + if (U>ma) { - U=motorParams.currentMa; + U=ma; } + //when error is positive we need to move reverse direction if (u>0) { @@ -1161,12 +1181,40 @@ int64_t StepperCtrl::calculatePhasePrediction(int64_t currentLoc) return x; } + +bool StepperCtrl::determineError(int64_t currentLoc,int64_t error) +{ + static int64_t lastLocation=0; + static int64_t lastError=0; + static int64_t lastVelocity=0; + + int64_t velocity; + + //since this is called on periodic timer the velocity + // is propotional to the change in location + // one rotation per second is velocity of 10, assumming 6khz update rate + // one rotation per minute is 10/60 velocity units + // since this is less than 1 we will scale the velo + velocity=(currentLoc-lastLocation); + + if (velocity>0 && lastVelocity>0) + { + + } + + + lastVelocity=velocity; + lastError=error; + lastLocation=currentLoc; +} + //this was written to do the PID loop not modeling a DC servo // but rather using features of stepper motor. bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control_t *ptrCtrl) { static uint32_t t0=0; static uint32_t calls=0; + bool ret=false; static int32_t maxError=0; static int32_t lastError=0; @@ -1174,13 +1222,24 @@ bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control static int32_t iTerm=0; //static int64_t lastY=getCurrentLocation(); static int32_t velocity=0; + static int32_t errorCount=0; + + static bool lastProbeState=false; + static int64_t probeStartAngle=0; + static int32_t maxMa=0; + + + static int64_t filteredError=0; + static int32_t probeCount=0; int32_t fullStep=ANGLE_STEPS/motorParams.fullStepsPerRotation; + int32_t ma=0; int64_t y; + //estimate our current location based on the encoder y=currentLoc; @@ -1203,8 +1262,9 @@ bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control { int64_t error; int32_t u; - int32_t ma; + int32_t x; + int32_t kp; //error is in units of degrees when 360 degrees == 65536 error=(desiredLoc-y);//measureError(); //error is currentPos-desiredPos @@ -1217,12 +1277,14 @@ bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control i=0; } - if (abs(error)fullStep) { x=fullStep; + iTerm=fullStep; } if (x<-fullStep) { x=-fullStep; + iTerm=-fullStep; } - u=(sPID.Kp * error)/CTRL_PID_SCALING+x+(sPID.Kd *(error-lastError))/CTRL_PID_SCALING; + u=(kp * error)/CTRL_PID_SCALING+x+(sPID.Kd *(error-lastError))/CTRL_PID_SCALING; //limit error to full step @@ -1250,16 +1314,63 @@ bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control u=-fullStep; } - ma=(abs(u)*(motorParams.currentMa-motorParams.currentHoldMa)) - / fullStep + motorParams.currentHoldMa; - - //ma=(abs(u)*(NVM->SystemParams.currentMa))/fullStep; - + ma=(abs(u)*(motorParams.currentMa-motorParams.currentHoldMa))/ fullStep + motorParams.currentHoldMa; if (ma>motorParams.currentMa) { ma=motorParams.currentMa; } + //maxMa=motorParams.currentMa; + + if (systemParams.homePin>=0) + { + + if (digitalRead(systemParams.homePin)==0) + { + if (lastProbeState==false) + { + //record our current angle for homing + probeStartAngle=desiredLoc; + probeCount=0; + maxMa=0; + } + lastProbeState=true; + probeCount++; + //we will lower current after whe have moved some amount + + if (probeCount > NZS_CONTROL_LOOP_HZ && probeCount <(2* NZS_CONTROL_LOOP_HZ)) + { + maxMa+=ma; + if (abs(error)>maxError) + { + maxError=abs(error); + } + + } + if (probeCount>(2*NZS_CONTROL_LOOP_HZ)) + { + // ma=(abs(u)*(maxMa))/ fullStep;// + motorParams.homeHoldMa; + // if (ma>motorParams.homeMa) + // { + // ma=motorParams.homeMa; + // } + + //if (ma>maxMa/NZS_CONTROL_LOOP_HZ) + { + ma=((maxMa/NZS_CONTROL_LOOP_HZ)*9)/10; + } + + } + } else + { + lastProbeState=false; + } + }else + { + maxError=0; + probeCount=0; + //maxMa=0; + } y=y+u; @@ -1272,12 +1383,45 @@ bool StepperCtrl::simpleFeedback(int64_t desiredLoc, int64_t currentLoc, Control //stepperDriver.limitCurrent(99); } - if (abs(lastError)>(systemParams.errorLimit)) + //filteredError=(filteredError*15+lastError)/16; + + if (probeCount>(2*NZS_CONTROL_LOOP_HZ)) { - return 1; + if (abs(lastError) > maxError ) + { + + errorCount++; + if (errorCount>(10)) + { + return 1; + } + return 0; + } + + } + else + { + if (abs(lastError) > systemParams.errorLimit) + { + + errorCount++; + if (errorCount>(NZS_CONTROL_LOOP_HZ/128)) // error needs to exist for some time period + { + return 1; + } + return 0; + } } + + if (errorCount>0) + { + errorCount--; + } + + //errorCount=0; stepperDriver.limitCurrent(99); //reduce noise on low error return 0; + } @@ -1394,9 +1538,18 @@ bool StepperCtrl::processFeedback(void) Control_t ctrl; int64_t desiredLoc; int64_t currentLoc; + int32_t steps; static int64_t mean=0;; us=micros(); + steps=getSteps(); + if (steps>0) + { + requestStep(1, (uint16_t)steps); + }else + { + requestStep(0, (uint16_t)(-steps)); + } desiredLoc=getDesiredLocation(); diff --git a/firmware/stepper_nano_zero/stepper_controller.h b/firmware/stepper_nano_zero/stepper_controller.h index 9a9b335..96f887c 100644 --- a/firmware/stepper_nano_zero/stepper_controller.h +++ b/firmware/stepper_nano_zero/stepper_controller.h @@ -133,6 +133,7 @@ class StepperCtrl void updateLocTable(int64_t desiredLoc, int64_t currentLoc,Control_t *ptrCtrl); int64_t calculatePhasePrediction(int64_t currentLoc); + bool determineError(int64_t currentLoc, int64_t error); public: uint16_t getStartupEncoder(void) {return startUpEncoder;} diff --git a/firmware/stepper_nano_zero/steppin.cpp b/firmware/stepper_nano_zero/steppin.cpp new file mode 100644 index 0000000..0f08505 --- /dev/null +++ b/firmware/stepper_nano_zero/steppin.cpp @@ -0,0 +1,170 @@ +#include "steppin.h" +#include "stepper_controller.h" +#include "wiring_private.h" + +extern StepperCtrl stepperCtrl; + +volatile int32_t stepsChanged=0; +#define WAIT_TC32_REGS_SYNC(x) while(x->COUNT32.STATUS.bit.SYNCBUSY); + +#if (PIN_STEP_INPUT != 0) +#error "this code only works with step pin being D0 (PA11, EXTINT11)" +#endif + +int32_t getSteps(void) +{ +#ifndef USE_NEW_STEP + return 0; +#endif + int32_t x; +#ifdef USE_TC_STEP + int32_t y; + + WAIT_TC32_REGS_SYNC(TC4) + x=(int32_t)TC4->COUNT32.COUNT.reg; + y=x-stepsChanged; + stepsChanged=x; + return y; + +#else + EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT11; + x=stepsChanged; + stepsChanged=0; + EIC->INTENSET.reg = EIC_INTENSET_EXTINT11; + return x; +#endif +} +//this function is called on the rising edge of a step from external device +static void stepInput(void) +{ + static int dir; + //read our direction pin + dir = digitalRead(PIN_DIR_INPUT); + + if (CW_ROTATION == NVM->SystemParams.dirPinRotation) + { + dir=!dir; //reverse the rotation + } + +#ifndef USE_NEW_STEP + stepperCtrl.requestStep(dir,1); +#else + if (dir) + { + stepsChanged++; + }else + { + stepsChanged--; + } +#endif +} + +void enableEIC(void) +{ + if (EIC->CTRL.bit.ENABLE == 0) + { + // Enable GCLK for IEC (External Interrupt Controller) + GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_EIC)); + + // Enable EIC + EIC->CTRL.bit.ENABLE = 1; + while (EIC->STATUS.bit.SYNCBUSY == 1) { } + } +} + + +void setupStepEvent(void) +{ + //we will set up the EIC to generate an even on rising edge of step pin + //make sure EIC is setup + enableEIC(); + + + // Assign step pin to EIC + // Step pin is PA11, EXTINT11 + pinPeripheral(PIN_STEP_INPUT, PIO_EXTINT); + + //***** setup EIC ****** + EIC->EVCTRL.bit.EXTINTEO11=1; //enable event for EXTINT11 + //setup up external interurpt 11 to be rising edge triggered + EIC->CONFIG[1].reg |= EIC_CONFIG_SENSE3(EIC_CONFIG_SENSE3_HIGH_Val); + + //diable actually generating an interrupt, we only want event triggered + EIC->INTENCLR.reg = EIC_INTENCLR_EXTINT11; + + //**** setup the event system *** + // Enable GCLK for EVSYS channel 0 + GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_EVSYS_CHANNEL_0)); + while (GCLK->STATUS.bit.SYNCBUSY); + EVSYS->CHANNEL.reg=EVSYS_CHANNEL_CHANNEL(0) + | EVSYS_CHANNEL_EDGSEL_RISING_EDGE + | EVSYS_CHANNEL_EVGEN(EVSYS_ID_GEN_EIC_EXTINT_11) + | EVSYS_CHANNEL_PATH_ASYNCHRONOUS; + + EVSYS->USER.reg = EVSYS_USER_CHANNEL(1) + | EVSYS_USER_USER(EVSYS_ID_USER_TC4_EVU); + + //**** setup the Timer counter ****** + // Enable GCLK for TC4 and TC5 (timer counter input clock) + GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)); + while (GCLK->STATUS.bit.SYNCBUSY); + + TC4->COUNT32.CTRLA.reg = TC_CTRLA_SWRST; //reset TC4 + WAIT_TC32_REGS_SYNC(TC4) + + TC4->COUNT32.CTRLA.reg = TC_CTRLA_MODE_COUNT32 // Set Timer counter Mode to 32 bits + | TC_CTRLA_WAVEGEN_MFRQ //normal counting mode (not using waveforms) + | TC_CTRLA_PRESCALER_DIV1; //count each pulse + WAIT_TC32_REGS_SYNC(TC4) + + TC4->COUNT32.CTRLBCLR.reg=0xFF; //clear all values. + WAIT_TC32_REGS_SYNC(TC4) + + TC4->COUNT32.EVCTRL.reg=TC_EVCTRL_TCEI | TC_EVCTRL_EVACT_COUNT; //enable event input and count + WAIT_TC32_REGS_SYNC(TC4) + + TC4->COUNT32.COUNT.reg=0; + WAIT_TC32_REGS_SYNC(TC4) + + // Enable TC + TC4->COUNT32.CTRLA.reg |= TC_CTRLA_ENABLE; + WAIT_TC32_REGS_SYNC(TC4) +} + +static void dirChanged_ISR(void) +{ + static int dir; + //read our direction pin + dir = digitalRead(PIN_DIR_INPUT); + + if (CW_ROTATION == NVM->SystemParams.dirPinRotation) + { + dir=!dir; //reverse the rotation + } + if (dir) + { + TC4->COUNT32.CTRLBSET.bit.DIR=1; + WAIT_TC32_REGS_SYNC(TC4) + } else + { + TC4->COUNT32.CTRLBCLR.bit.DIR=1; + WAIT_TC32_REGS_SYNC(TC4) + } +} + + +void stepPinSetup(void) +{ + + +#ifdef USE_TC_STEP + //attachInterrupt configures the EIC as highest priority interrupts. + attachInterrupt(digitalPinToInterrupt(PIN_DIR_INPUT), dirChanged_ISR, CHANGE); + setupStepEvent(); + + +#else + attachInterrupt(digitalPinToInterrupt(PIN_STEP_INPUT), stepInput, RISING); +#endif + +} diff --git a/firmware/stepper_nano_zero/steppin.h b/firmware/stepper_nano_zero/steppin.h new file mode 100644 index 0000000..2488b8d --- /dev/null +++ b/firmware/stepper_nano_zero/steppin.h @@ -0,0 +1,10 @@ +#ifndef __STEPPIN_H___ +#define __STEPPIN_H___ +#include "board.h" + +void stepPinSetup(void); //setup step pin + +int32_t getSteps(void); //returns the number of steps changed since last call + + +#endif // __STEPPIN_H___