mirror of
https://github.com/eddyem/mmpp.git
synced 2025-12-06 10:35:16 +03:00
beta-version, tested @ breadbord
This commit is contained in:
parent
025d323135
commit
23396af35b
@ -9,18 +9,129 @@ Based on STM32F030F4P6
|
||||
|:---|:----:|:------------------------|
|
||||
|PA0 | AIN | Steppers current |
|
||||
|PA1 | AIN | Input voltage 12V |
|
||||
|PA2 | AIN | EndSwitch2 of motor1 |
|
||||
|PA3 | AIN | EndSwitch1 of motor1 |
|
||||
|PA4 | PUPD | Tim14Ch1 - motor1 steps |
|
||||
|PA5 | PUPD | Motor2 enable |
|
||||
|PA6 | PUPD | Tim3Ch1 - motor2 steps |
|
||||
|PA7 | PUPD | Motor2 direction |
|
||||
|PA2 | AIN | EndSwitch1 of motor0 |
|
||||
|PA3 | AIN | EndSwitch0 of motor0 |
|
||||
|PA4 | PUPD | Tim14Ch1 - motor0 steps |
|
||||
|PA5 | PUPD | Motor1 enable |
|
||||
|PA6 | PUPD | Tim3Ch1 - motor1 steps |
|
||||
|PA7 | PUPD | Motor1 direction |
|
||||
|PA9 | OD | USART1 Tx |
|
||||
|PA10| FIN | USART1 Rx |
|
||||
|PA13| AIN | EndSwitch1 of motor2 |
|
||||
|PA14| AIN | EndSwitch2 of motor2 |
|
||||
|PB1 | PUPD | Turn off motors' power |
|
||||
|PF0 | PUPD | Motor1 enable |
|
||||
|PF1 | PUPD | Motor1 direction |
|
||||
|PA13| FIN | EndSwitch0 of motor1 |
|
||||
|PA14| FIN | EndSwitch1 of motor1 |
|
||||
|PB1 | PUPD | Turn off current sensor |
|
||||
|PF0 | PUPD | Motor0 enable |
|
||||
|PF1 | PUPD | Motor0 direction |
|
||||
|
||||
## Protocol
|
||||
|
||||
Any command have format "# CMD", where # is device ID (the_conf.devID) or "-1" if there's
|
||||
only one device at the bus. After it can be any number of spaces and command symbols.
|
||||
|
||||
### First symbol of commands
|
||||
|
||||
* (nothing except spaces) - *ping* command, device with given ID answers: `ALIVE`
|
||||
* **G** - one of the *Getters* (depending on next text)
|
||||
* **S** - one of the *Setters*
|
||||
* **R** - make *MCU software reboot* (next `status` getter will return `SOFTRESET=1`)
|
||||
* **W** - *write flash* command, use it to save new configuration data
|
||||
|
||||
All wrong commands will return `BADCMD`, commands with bad format or wrong number return `ERR`.
|
||||
Commands with lot of output ends with `DATAEND`. Some commands (like flash write) will return
|
||||
just `ALL OK` if succeed.
|
||||
|
||||
### Getters
|
||||
|
||||
Getters returning more than one field ends with `DATAEND` meaning that's all data.
|
||||
|
||||
* **A** - get *ADC value*
|
||||
* **D** - Vdd value (*100 Volts), e.g. `VDD=330`
|
||||
* **I** - total motors' current (*100 Amperes), e.g. `IMOT=123`
|
||||
* **M** - motor's voltage (*100 Volts), e.g. `VMOT=1193`
|
||||
* **C** - get *current configuration*, e.g.
|
||||
|
||||
```
|
||||
CONFSZ=36
|
||||
DEVID=0
|
||||
V12NUM=1
|
||||
V12DEN=10
|
||||
I12NUM=1
|
||||
I12DEN=1
|
||||
V33NUM=1
|
||||
V33DEN=1
|
||||
ESWTHR=150
|
||||
MOT0SPD=60
|
||||
MOT1SPD=60
|
||||
USARTSPD=115200
|
||||
REVERSE0=0
|
||||
REVERSE1=0
|
||||
MAXSTEPS0=0
|
||||
MAXSTEPS1=0
|
||||
DATAEND
|
||||
```
|
||||
|
||||
All variables here are fields of `user_conf` struct.
|
||||
|
||||
|
||||
* **R** - get *raw ADC* values, e.g.
|
||||
|
||||
```
|
||||
ADC[0]=1991
|
||||
ADC[1]=124
|
||||
ADC[2]=1351
|
||||
ADC[3]=1909
|
||||
ADC[4]=0
|
||||
ADC[5]=0
|
||||
ADC[6]=1707
|
||||
ADC[7]=1531
|
||||
DATAEND
|
||||
```
|
||||
|
||||
* **S** - get *motors' status*, e.g.
|
||||
|
||||
```
|
||||
SOFTRESET=1
|
||||
MOTOR0=STOP
|
||||
POS0=-1
|
||||
ESW00=ERR
|
||||
ESW01=BTN
|
||||
MOTOR1=STOPPOS1=-1
|
||||
ESW10=HALL
|
||||
ESW11=HALL
|
||||
|
||||
```
|
||||
|
||||
* **T** - get *MCU temperature*, e.g. `TEMP=365`
|
||||
|
||||
### Setters
|
||||
Change of any setter takes place in MCU RAM immediately. To store them permanently run
|
||||
*write flash* command.
|
||||
|
||||
* **C#num** - set current *speed* to *num* for motor #
|
||||
* **D num** - set *denominator* to number *num*
|
||||
* **E num** - set *numerator*
|
||||
* **I num** - set *device ID*
|
||||
* **M#num** - set maxsteps (*num* is 1..65535) for motor `#`
|
||||
* **R#num** - set reverse for motor # (*num* == 0 turns reverse off, *num* == 1 turns it on)
|
||||
* **S#num** - set *speed* (`motspd`) to *num* for motor #
|
||||
* **T num** - set *end-switches threshold* (in ADU, near 0 for Hall switch, 2048 for user button
|
||||
and 4096 for released state)
|
||||
* **U num** - set *USART speed* to *num* bits per second
|
||||
|
||||
### Motor speed setters
|
||||
To set motor speed to **N** steps per second, give command `C` or `S` with argument equal to
|
||||
3000/N. E.g. to set current speed for DevID=0, motor0 to 50 steps per second give command `0SC050`.
|
||||
|
||||
### Denominator and numerator setters
|
||||
Have naxt letter similar to ADC getter (**D** - Vdd, **I** - motors' I, or **M** - motors' U).
|
||||
The value of numerator shouldn't be very large as uint32_t used in multiplications.
|
||||
|
||||
### Device ID setter
|
||||
After this command device will immediately change it's ID, if you "lost" device after this
|
||||
procedure you should reboot it or (if there's only one device on the bus) call it by "universal ID"
|
||||
(-1).
|
||||
|
||||
### USART speed setter
|
||||
The USART speed will be changed after next reset (e.g. by *MCU software reboot* command), so it
|
||||
don't work without storing in the flash. Check it twice before writing as wrong numbers can make device
|
||||
lost until next re-flashing.
|
||||
|
||||
@ -36,10 +36,8 @@ static uint32_t VddValue = 0; // value of Vdd * 100 (for more precision measurem
|
||||
* 1 - Input voltage 12V
|
||||
* 2 - EndSwitch2 of motor1
|
||||
* 3 - EndSwitch1 of motor1
|
||||
* 4 - EndSwitch1 of motor2
|
||||
* 5 - EndSwitch2 of motor2
|
||||
* 6 - inner temperature
|
||||
* 7 - vref
|
||||
* 4 - inner temperature
|
||||
* 5 - vref
|
||||
*/
|
||||
uint16_t ADC_array[NUMBER_OF_ADC_CHANNELS];
|
||||
|
||||
@ -67,14 +65,13 @@ void adc_setup(){
|
||||
}while ((ADC1->ISR & ADC_ISR_ADRDY) == 0) /* (2) */;
|
||||
/* (1) Select HSI14 by writing 00 in CKMODE (reset value) */
|
||||
/* (2) Select the continuous mode */
|
||||
/* (3) Select CHSEL0..3, 13,14, 16,17 */
|
||||
/* (3) Select CHSEL0..3, 16,17 */
|
||||
/* (4) Select a sampling mode of 111 i.e. 239.5 ADC clk to be greater than 17.1us */
|
||||
/* (5) Wake-up the VREFINT and Temperature sensor (only for VBAT, Temp sensor and VRefInt) */
|
||||
// ADC1->CFGR2 &= ~ADC_CFGR2_CKMODE; /* (1) */
|
||||
ADC1->CFGR1 |= ADC_CFGR1_CONT; /* (2)*/
|
||||
ADC1->CHSELR = ADC_CHSELR_CHSEL0 | ADC_CHSELR_CHSEL1 | ADC_CHSELR_CHSEL2 |
|
||||
ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL13 | ADC_CHSELR_CHSEL14 |
|
||||
ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; /* (3)*/
|
||||
ADC_CHSELR_CHSEL3 | ADC_CHSELR_CHSEL16 | ADC_CHSELR_CHSEL17; /* (3)*/
|
||||
ADC1->SMPR |= ADC_SMPR_SMP_0 | ADC_SMPR_SMP_1 | ADC_SMPR_SMP_2; /* (4) */
|
||||
ADC->CCR |= ADC_CCR_TSEN | ADC_CCR_VREFEN; /* (5) */
|
||||
// DMA for AIN
|
||||
@ -99,7 +96,8 @@ void adc_setup(){
|
||||
int32_t getTemp(){
|
||||
CHKVDDTIME();
|
||||
// make correction on Vdd value
|
||||
int32_t temperature = (int32_t)ADC_array[6] * VddValue / 330;
|
||||
int32_t temperature = (int32_t)ADC_array[4] * VddValue / 330;
|
||||
/*
|
||||
write2trbuf("getTemp()\ncal30=");
|
||||
put_uint(*TEMP30_CAL_ADDR);
|
||||
write2trbuf(", cal110=");
|
||||
@ -107,72 +105,87 @@ put_uint(*TEMP110_CAL_ADDR);
|
||||
write2trbuf(", t=");
|
||||
put_int(temperature);
|
||||
SENDBUF();
|
||||
*/
|
||||
temperature = (int32_t) *TEMP30_CAL_ADDR - temperature;
|
||||
/*
|
||||
put_int(temperature);
|
||||
SENDBUF();
|
||||
*/
|
||||
temperature *= (int32_t)(1100 - 300);
|
||||
/*
|
||||
put_int(temperature);
|
||||
SENDBUF();
|
||||
*/
|
||||
temperature = temperature / (int32_t)(*TEMP30_CAL_ADDR - *TEMP110_CAL_ADDR);
|
||||
/*
|
||||
put_int(temperature);
|
||||
SENDBUF();
|
||||
*/
|
||||
temperature += 300;
|
||||
return(temperature);
|
||||
}
|
||||
|
||||
//static uint32_t calval = 0;
|
||||
// return Vdd * 10 (V)
|
||||
// return Vdd * 100 (V)
|
||||
uint32_t getVdd(){
|
||||
#define ARRSZ (10)
|
||||
static uint16_t arr[ARRSZ] = {0};
|
||||
static int arridx = 0;
|
||||
uint32_t v = ADC_array[7];
|
||||
uint32_t v = ADC_array[5];
|
||||
int i;
|
||||
/*
|
||||
write2trbuf("getVdd(), val=");
|
||||
put_uint(v);
|
||||
write2trbuf(", cal=");
|
||||
put_uint(*VREFINT_CAL_ADDR);
|
||||
SENDBUF();
|
||||
*/
|
||||
if(arr[0] == 0){ // first run - fill all with current data
|
||||
/*
|
||||
write2trbuf("1st run");
|
||||
SENDBUF();
|
||||
*/
|
||||
for(i = 0; i < ARRSZ; ++i) arr[i] = (uint16_t) v;
|
||||
}else{
|
||||
/*
|
||||
write2trbuf("arridx=");
|
||||
put_int(arridx);
|
||||
SENDBUF();
|
||||
*/
|
||||
arr[arridx++] = v;
|
||||
v = 0; // now v is mean
|
||||
if(arridx > ARRSZ-1) arridx = 0;
|
||||
// calculate mean
|
||||
for(i = 0; i < ARRSZ; ++i){
|
||||
/*
|
||||
write2trbuf("arr["); put2trbuf('0'+i); write2trbuf("]=");
|
||||
put_uint(arr[i]);
|
||||
SENDBUF();
|
||||
*/
|
||||
v += arr[i];
|
||||
}
|
||||
v /= ARRSZ;
|
||||
/*
|
||||
write2trbuf("mean value: ");
|
||||
put_uint(v);
|
||||
SENDBUF();
|
||||
*/
|
||||
}
|
||||
/* if(!calval){
|
||||
calval = ((uint32_t) *VREFINT_CAL_ADDR) * VDD_CALIB;
|
||||
calval /= VDD_APPLI;
|
||||
} */
|
||||
uint32_t vdd = ((uint32_t) *VREFINT_CAL_ADDR) * (uint32_t)330 * the_conf.v33numerator; // 3.3V
|
||||
/*
|
||||
put_uint(vdd);
|
||||
SENDBUF();
|
||||
//vdd /= calval * the_conf.v33denominator;
|
||||
*/
|
||||
vdd /= v * the_conf.v33denominator;
|
||||
/*
|
||||
put_uint(vdd);
|
||||
SENDBUF();
|
||||
*/
|
||||
lastVddtime = Tms;
|
||||
VddValue = vdd;
|
||||
return vdd/10;
|
||||
return vdd;
|
||||
}
|
||||
|
||||
// return value of 12V * 10 (V)
|
||||
// return value of 12V * 100 (V)
|
||||
uint32_t getVmot(){
|
||||
CHKVDDTIME();
|
||||
uint32_t vmot = ADC_array[1] * VddValue * the_conf.v12numerator;
|
||||
@ -195,12 +208,17 @@ uint32_t getImot(){
|
||||
// @param eswnum - switch number (0,1)
|
||||
ESW_status eswStatus(int motnum, int eswnum){
|
||||
int idx;
|
||||
if(motnum){ // motor 1
|
||||
if(eswnum) idx = 5;
|
||||
else idx = 4;
|
||||
if(motnum){ // motor 1 have no ADC - just 0 or 1
|
||||
if(eswnum){ // ESW11 - PA14
|
||||
if(GPIOA->IDR & 1<<14) return ESW_RELEASED;
|
||||
else return ESW_HALL;
|
||||
}else{ // ESW10 - PA13
|
||||
if(GPIOA->IDR & 1<<13) return ESW_RELEASED;
|
||||
else return ESW_HALL;
|
||||
}
|
||||
}else{ // motor 0
|
||||
if(eswnum) idx = 3;
|
||||
else idx = 2;
|
||||
if(eswnum) idx = 2;
|
||||
else idx = 3;
|
||||
}
|
||||
uint16_t thres = the_conf.ESW_thres, val = ADC_array[idx];
|
||||
// low sighal: 0..threshold - Hall activated
|
||||
|
||||
@ -26,7 +26,7 @@
|
||||
#define __ADC_H__
|
||||
|
||||
// 8 channels (including inttemp & vrefint)
|
||||
#define NUMBER_OF_ADC_CHANNELS (8)
|
||||
#define NUMBER_OF_ADC_CHANNELS (6)
|
||||
|
||||
extern uint16_t ADC_array[];
|
||||
void adc_setup();
|
||||
|
||||
@ -35,15 +35,15 @@ user_conf the_conf = {
|
||||
.userconf_sz = sizeof(user_conf)
|
||||
,.devID = 0
|
||||
,.v12numerator = 1
|
||||
,.v12denominator = 10
|
||||
,.v12denominator = 1
|
||||
,.i12numerator = 1
|
||||
,.i12denominator = 1
|
||||
,.v33denominator = 1
|
||||
,.v33numerator = 1
|
||||
,.ESW_thres = 150
|
||||
,.ESW_thres = 500
|
||||
,.usartspd = (uint32_t)115200
|
||||
,.motspd = {60, 60} // max speed: 3000/60 = 50 steps per second
|
||||
,.maxsteps = {0, 0} // max steps from point to point - infinity
|
||||
,.motspd = {10, 10} // max speed: 300 steps per second
|
||||
,.maxsteps = {50000, 50000} // max steps from point to point
|
||||
,.reverse = {0,0} // set DIR to this value when moving to '+'
|
||||
};
|
||||
|
||||
|
||||
@ -37,7 +37,7 @@ typedef struct{
|
||||
uint16_t v33numerator; // 3.3V (vref)
|
||||
uint16_t v33denominator;
|
||||
uint32_t usartspd; // usartspeed
|
||||
uint16_t motspd[2]; // motors speed dividers (3kHz/motxspd per step)
|
||||
uint16_t motspd[2]; // max motor speed ([3000 / motspd] steps per second)
|
||||
uint16_t maxsteps[2]; // maximum amount of steps for each motor (0 - infinity)
|
||||
uint8_t reverse[2]; // == 1 if positive direction when DIR is low
|
||||
} user_conf;
|
||||
|
||||
@ -45,15 +45,17 @@ void sys_tick_handler(void){
|
||||
static void gpio_setup(void){
|
||||
// Enable clocks to the GPIO subsystems
|
||||
RCC->AHBENR |= RCC_AHBENR_GPIOAEN | RCC_AHBENR_GPIOBEN | RCC_AHBENR_GPIOFEN;
|
||||
// PA0..3, PA13, PA14 - AIN; PA4..7 - PUPD;
|
||||
GPIOA->MODER = GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI | GPIO_MODER_MODER2_AI |
|
||||
GPIO_MODER_MODER3_AI | GPIO_MODER_MODER13_AI | GPIO_MODER_MODER14_AI |
|
||||
GPIO_MODER_MODER4_O | GPIO_MODER_MODER5_O | GPIO_MODER_MODER6_O | GPIO_MODER_MODER7_O;
|
||||
// prepare levels @ ~EN pins (1 disable drivers)
|
||||
stp_disable();
|
||||
// PA0..3, PA13, PA14 - floating input with pullup; PA5,7 - PUPD; PA4,6 - AF
|
||||
GPIOA->OSPEEDR = 0; // all low speed
|
||||
GPIOA->PUPDR = 0; // clear pull-down for PA14&PA13
|
||||
GPIOA->PUPDR = GPIO_PUPDR_PUPDR13_0 | GPIO_PUPDR_PUPDR14_0;
|
||||
// PA4 - Tim14Ch1 (AF4), PA6 - Tim3Ch1 (AF1)
|
||||
GPIOA->AFR[0] = (GPIOA->AFR[0] &~ (GPIO_AFRL_AFRL4 | GPIO_AFRL_AFRL6))\
|
||||
| (4 << (4 * 4)) | (1 << (6 * 4));
|
||||
GPIOA->MODER = GPIO_MODER_MODER0_AI | GPIO_MODER_MODER1_AI | GPIO_MODER_MODER2_AI |
|
||||
GPIO_MODER_MODER3_AI | GPIO_MODER_MODER4_AF | GPIO_MODER_MODER5_O |
|
||||
GPIO_MODER_MODER6_AF | GPIO_MODER_MODER7_O;
|
||||
// PB1 - PUPD
|
||||
GPIOB->MODER = GPIO_MODER_MODER1_O;
|
||||
// PF0, PF1 - PUPD
|
||||
@ -102,9 +104,10 @@ int main(void){
|
||||
while (1){
|
||||
IWDG->KR = IWDG_REFRESH; // refresh watchdog
|
||||
if(lastT > Tms || Tms - lastT > 499){
|
||||
#ifdef EBUG
|
||||
/* #ifdef EBUG
|
||||
pin_toggle(GPIOA, 1<<4); // blink by onboard LED once per second
|
||||
#endif
|
||||
*/
|
||||
lastT = Tms;
|
||||
}
|
||||
if(usart1rx()){ // usart1 received data, store in in buffer
|
||||
|
||||
@ -41,6 +41,7 @@ static const char *err = "ERR";
|
||||
static char *getnum(char *buf, int32_t *N);
|
||||
static char *get_something(char *str);
|
||||
static char *set_something(char *str);
|
||||
static char *motor_cmd(char *str);
|
||||
|
||||
static char *get_status();
|
||||
static char *get_conf();
|
||||
@ -52,7 +53,8 @@ static char *setDenEn(uint8_t De, char *str);
|
||||
static char *setDevId(char *str);
|
||||
static char *setESWthres(char *str);
|
||||
static char *setUSARTspd(char *str);
|
||||
|
||||
static char *setmotvals(char v, char *str);
|
||||
static char *setMotSpeed(int cur, char *str);
|
||||
|
||||
#define omitwsp(str) do{register char nxt; while((nxt = *str)){if(nxt != ' ' && nxt != '\t') break; else ++str;}}while(0)
|
||||
|
||||
@ -78,6 +80,9 @@ char* process_command(char *cmdbuf){
|
||||
case 'G': // get something
|
||||
return get_something(str);
|
||||
break;
|
||||
case 'M': // motors' management
|
||||
return motor_cmd(str);
|
||||
break;
|
||||
case 'R':
|
||||
NVIC_SystemReset();
|
||||
break;
|
||||
@ -147,7 +152,7 @@ static char *get_something(char *str){
|
||||
case 'S': // get motors' status
|
||||
return get_status();
|
||||
break;
|
||||
case 'T':
|
||||
case 'T': // get MCU temperature
|
||||
return get_temper();
|
||||
break;
|
||||
}
|
||||
@ -158,21 +163,52 @@ static char *get_status(){
|
||||
int i, j;
|
||||
char str[3] = {0, '=', 0};
|
||||
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
|
||||
write2trbuf("WDGRESET=1");
|
||||
write2trbuf("WDGRESET=1\n");
|
||||
}
|
||||
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
|
||||
write2trbuf("SOFTRESET=1");
|
||||
write2trbuf("SOFTRESET=1\n");
|
||||
}
|
||||
RCC->CSR = RCC_CSR_RMVF; // clear reset flags
|
||||
for(i = 0; i < 2; ++i){
|
||||
write2trbuf("MOTOR"); str[0] = '0' + i;
|
||||
write2trbuf(str);
|
||||
if(stp_isactive(i)){
|
||||
write2trbuf("MOV\nSTEPSLEFT");
|
||||
stp_state stt = stp_getstate(i);
|
||||
if(STP_SLEEP != stt){
|
||||
char *s;
|
||||
switch(stt){
|
||||
case STP_ACCEL:
|
||||
s = "ACCEL";
|
||||
break;
|
||||
case STP_DECEL:
|
||||
s = "DECEL";
|
||||
break;
|
||||
case STP_MOVE:
|
||||
s = "MOVE";
|
||||
break;
|
||||
case STP_MOVE0:
|
||||
s = "MOVETO0";
|
||||
break;
|
||||
case STP_MOVE1:
|
||||
s = "MOVETO1";
|
||||
break;
|
||||
case STP_MVSLOW:
|
||||
s = "MVSLOW";
|
||||
break;
|
||||
case STP_STOP:
|
||||
s = "STOP";
|
||||
break;
|
||||
case STP_STOPZERO:
|
||||
s = "STOPZERO";
|
||||
break;
|
||||
default:
|
||||
s = "UNKNOWN";
|
||||
}
|
||||
write2trbuf(s);
|
||||
write2trbuf("\nSTEPSLEFT");
|
||||
write2trbuf(str);
|
||||
put_uint(stp_stepsleft(i));
|
||||
}else write2trbuf("STOP");
|
||||
write2trbuf("POS");
|
||||
}else write2trbuf("SLEEP");
|
||||
write2trbuf("\nPOS");
|
||||
write2trbuf(str);
|
||||
put_int(stp_position(i));
|
||||
SENDBUF();
|
||||
@ -218,6 +254,8 @@ static const user_conf_descr descrarr[] = {
|
||||
{"ESWTHR", &the_conf.ESW_thres},
|
||||
{"MOT0SPD",&the_conf.motspd[0]},
|
||||
{"MOT1SPD",&the_conf.motspd[1]},
|
||||
{"MAXSTEPS0",&the_conf.maxsteps[0]},
|
||||
{"MAXSTEPS1",&the_conf.maxsteps[1]},
|
||||
{NULL, NULL}
|
||||
};
|
||||
|
||||
@ -236,6 +274,7 @@ static char *get_conf(){
|
||||
put_uint(the_conf.reverse[0]);
|
||||
write2trbuf("\nREVERSE1=");
|
||||
put_uint(the_conf.reverse[1]);
|
||||
SENDBUF();
|
||||
return EODATA;
|
||||
}
|
||||
|
||||
@ -284,6 +323,9 @@ static char *get_temper(){
|
||||
|
||||
static char *set_something(char *str){
|
||||
switch(*str++){
|
||||
case 'C': // set current speed
|
||||
return setMotSpeed(1, str);
|
||||
break;
|
||||
case 'D': // set denominator
|
||||
return setDenEn(1, str);
|
||||
break;
|
||||
@ -293,6 +335,15 @@ static char *set_something(char *str){
|
||||
case 'I': // set device ID
|
||||
return setDevId(str);
|
||||
break;
|
||||
case 'M': // set maxsteps
|
||||
setmotvals('M', str);
|
||||
break;
|
||||
case 'R': // set reverse
|
||||
setmotvals('R', str);
|
||||
break;
|
||||
case 'S': // set speed
|
||||
return setMotSpeed(0, str);
|
||||
break;
|
||||
case 'T': // set endsw threshold
|
||||
return setESWthres(str);
|
||||
break;
|
||||
@ -347,3 +398,82 @@ static char *setUSARTspd(char *str){
|
||||
the_conf.usartspd = (uint32_t) N32;
|
||||
return ALLOK;
|
||||
}
|
||||
|
||||
// if cur == 1 set current speed else set global motspd
|
||||
static char *setMotSpeed(int cur, char *str){
|
||||
omitwsp(str);
|
||||
uint8_t Num = *str++ - '0';
|
||||
if(Num > 1) return ERR;
|
||||
int32_t spd;
|
||||
omitwsp(str);
|
||||
if(!getnum(str, &spd)) return ERR;
|
||||
if(spd < 2 || spd > 6553) return "BadSpd";
|
||||
if(cur){ // change current speed
|
||||
stp_chARR(Num, spd);
|
||||
}else{
|
||||
the_conf.motspd[Num] = spd;
|
||||
stp_chspd();
|
||||
}
|
||||
return ALLOK;
|
||||
}
|
||||
|
||||
// set other motor values
|
||||
static char *setmotvals(char v, char *str){
|
||||
omitwsp(str);
|
||||
uint8_t Num = *str++ - '0';
|
||||
if(Num > 1) return ERR;
|
||||
omitwsp(str);
|
||||
int32_t val;
|
||||
if(!getnum(str, &val)) return ERR;
|
||||
if(val < 0 || val > 0xffff) return "BadUINT16";
|
||||
switch(v){
|
||||
case 'M': // maxsteps
|
||||
if(val == 0) return ERR;
|
||||
the_conf.maxsteps[Num] = val;
|
||||
break;
|
||||
case 'R': // reverse
|
||||
if(val && val != 1) return ERR;
|
||||
the_conf.reverse[Num] = val;
|
||||
break;
|
||||
default: return ERR;
|
||||
}
|
||||
return ALLOK;
|
||||
}
|
||||
|
||||
// process motor command: start/stop
|
||||
static char *motor_cmd(char *str){
|
||||
omitwsp(str);
|
||||
uint8_t Num = *str++ - '0';
|
||||
int32_t steps;
|
||||
stp_status st;
|
||||
if(Num > 1) return "Num>1";
|
||||
omitwsp(str);
|
||||
switch(*str++){
|
||||
case 'M':
|
||||
omitwsp(str);
|
||||
if(!getnum(str, &steps)) return "BadSteps";
|
||||
st = stp_move(Num, steps);
|
||||
switch(st){
|
||||
case STPS_ACTIVE:
|
||||
return "IsMoving";
|
||||
break;
|
||||
case STPS_ONESW:
|
||||
return "OnEndSwitch";
|
||||
break;
|
||||
case STPS_ZEROMOVE:
|
||||
return "ZeroMove";
|
||||
break;
|
||||
case STPS_TOOBIG:
|
||||
return "TooBigNumber";
|
||||
break;
|
||||
default:
|
||||
return ALLOK;
|
||||
}
|
||||
break;
|
||||
case 'S':
|
||||
stp_stop(Num);
|
||||
return ALLOK;
|
||||
break;
|
||||
}
|
||||
return ERR;
|
||||
}
|
||||
|
||||
Binary file not shown.
@ -24,6 +24,7 @@
|
||||
#include "steppers.h"
|
||||
#include "flash.h"
|
||||
#include "adc.h"
|
||||
#include "usart.h"
|
||||
|
||||
// amount of steps need for full acceleration/deceleration cycle
|
||||
#define ACCDECSTEPS (50)
|
||||
@ -31,8 +32,8 @@
|
||||
#define USTEPS (16)
|
||||
|
||||
static GPIO_TypeDef* const MPORT[2] = {GPIOF, GPIOA};
|
||||
static const uint16_t MENPIN[2] = { 0, 1 << 5}; // enable pins: PF0 and PA5
|
||||
static const uint16_t MDIRPIN[2] = { 1, 1 << 7}; // direction pins: PF1 and PA7
|
||||
static const uint16_t MENPIN[2] = { 1<<0, 1 << 5}; // enable pins: PF0 and PA5
|
||||
static const uint16_t MDIRPIN[2] = { 1<<1, 1 << 7}; // direction pins: PF1 and PA7
|
||||
|
||||
int32_t mot_position[2] = {-1, -1}; // current position of motor (from zero endswitch, -1 means inactive)
|
||||
uint32_t steps_left[2] = {0,0}; // amount of steps left
|
||||
@ -42,35 +43,48 @@ static uint16_t stplowarr[2], stphigharr[2], stpsteparr[2];
|
||||
static int8_t dir[2] = {0,0}; // moving direction: -1 (negative) or 1 (positive)
|
||||
|
||||
// return 1 if motor is in active state
|
||||
int stp_isactive(int motnum){
|
||||
if(state[motnum] == STP_SLEEP) return 0;
|
||||
return 1;
|
||||
stp_state stp_getstate(int motnum){
|
||||
return state[motnum];
|
||||
}
|
||||
|
||||
// turn ~EN to 1 for both motors
|
||||
void stp_disable(){
|
||||
pin_set(MPORT[0], MENPIN[0]);
|
||||
pin_set(MPORT[1], MENPIN[1]);
|
||||
}
|
||||
|
||||
void stp_chspd(){
|
||||
int i;
|
||||
for(i = 0; i < 2; ++i){
|
||||
uint16_t spd = the_conf.motspd[i] << 4;
|
||||
if(spd && spd < 6553){
|
||||
uint16_t spd = the_conf.motspd[i];
|
||||
stplowarr[i] = spd;
|
||||
stphigharr[i] = spd * 10;
|
||||
stpsteparr[i] = (spd * 9) / ACCDECSTEPS + 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Tim3_ch1 - PA6, Tim14ch1 - PA4; 48MHz -> 48kHz
|
||||
static void timers_setup(){
|
||||
RCC->APB1ENR |= RCC_APB1ENR_TIM3EN | RCC_APB1ENR_TIM14EN; // enable clocking
|
||||
TIM3->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1; // PWM mode 1: acive->inactive, preload enable
|
||||
//TIM3->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0; // PWM mode 2: inacive->active, preload enable
|
||||
TIM3->CCMR1 = TIM_CCMR1_OC1M_2; // Force inactive
|
||||
TIM3->PSC = 999; // 48kHz
|
||||
TIM3->CCER = TIM_CCER_CC1P | TIM_CCER_CC1E; // turn it on, active low
|
||||
TIM3->DIER = TIM_DIER_UIE; // update interrupt
|
||||
TIM14->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1;
|
||||
//TIM3->CCER = TIM_CCER_CC1P | TIM_CCER_CC1E; // turn it on, active low
|
||||
TIM3->CCER = TIM_CCER_CC1E; // turn it on, active high
|
||||
TIM3->CCR1 = 1; // 20.8us for pulse duration, according to datasheet 1.9us is enough
|
||||
TIM3->ARR = 1000; // starting ARR value
|
||||
//TIM14->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0;
|
||||
TIM14->CCMR1 = TIM_CCMR1_OC1M_2;
|
||||
TIM14->PSC = 999;
|
||||
TIM14->CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
|
||||
TIM14->DIER = TIM_DIER_UIE;
|
||||
// enable IRQ
|
||||
//TIM14->CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
|
||||
TIM14->CCER = TIM_CCER_CC1E;
|
||||
TIM14->CCR1 = 1;
|
||||
TIM14->ARR = 1000;
|
||||
// enable IRQ & update values
|
||||
TIM3->EGR = TIM_EGR_UG;
|
||||
TIM14->EGR = TIM_EGR_UG;
|
||||
TIM3->DIER = TIM_DIER_CC1IE; // allow CC interrupt (we should count steps)
|
||||
TIM14->DIER = TIM_DIER_CC1IE;
|
||||
NVIC_EnableIRQ(TIM3_IRQn);
|
||||
NVIC_SetPriority(TIM3_IRQn, 0);
|
||||
NVIC_EnableIRQ(TIM14_IRQn);
|
||||
@ -79,49 +93,90 @@ static void timers_setup(){
|
||||
|
||||
// setup timers
|
||||
void stp_setup(){
|
||||
timers_setup();
|
||||
stp_chspd();
|
||||
timers_setup();
|
||||
}
|
||||
|
||||
// check end-switches for stepper motors
|
||||
void stp_process(){
|
||||
static uint16_t lastbtnpressed = 0; // anticlash counter
|
||||
int i = 0;
|
||||
for(i = 0; i < 2; ++i){
|
||||
stp_state curst = state[i];
|
||||
ESW_status esw[2];
|
||||
// check ESW0 for buttons
|
||||
esw[0] = eswStatus(0, 0);
|
||||
esw[1] = eswStatus(0, 1);
|
||||
if(esw[0] == ESW_BUTTON || esw[1] == ESW_BUTTON){
|
||||
if(lastbtnpressed++ == 3){ // stop all motors @ button
|
||||
//~ write2trbuf("1stpress");
|
||||
//~ SENDBUF();
|
||||
uint8_t stopped = 0;
|
||||
if(state[0] != STP_SLEEP){
|
||||
//~ write2trbuf("stopmot0");
|
||||
//~ SENDBUF();
|
||||
state[0] = STP_STOP;
|
||||
stopped = 1;
|
||||
}
|
||||
if(state[1] != STP_SLEEP){
|
||||
//~ write2trbuf("stopmot1");
|
||||
//~ SENDBUF();
|
||||
state[1] = STP_STOP;
|
||||
stopped = 1;
|
||||
}
|
||||
if(stopped) lastbtnpressed = 111; // override value
|
||||
}else if(lastbtnpressed == 100){ // one or both buttons pressed, run only after ~100ms
|
||||
//~ write2trbuf("lastbtnpressed");
|
||||
//~ SENDBUF();
|
||||
if(esw[0] == ESW_BUTTON && esw[1] == ESW_BUTTON){
|
||||
//~ write2trbuf("both");
|
||||
//~ SENDBUF();
|
||||
// both buttons pressed - move MOTOR1 to zero
|
||||
state[1] = STP_MOVE0;
|
||||
}else{ // move motor 0 to 0 or 1
|
||||
//~ write2trbuf("single");
|
||||
//~ SENDBUF();
|
||||
if(esw[0] == ESW_BUTTON) state[0] = STP_MOVE0;
|
||||
else state[0] = STP_MOVE1;
|
||||
}
|
||||
}
|
||||
}else lastbtnpressed = 0;
|
||||
|
||||
for(i = 0; i < 2; ++i){ // check motors' status
|
||||
stp_state curst = state[i];
|
||||
esw[0] = eswStatus(i, 0);
|
||||
esw[1] = eswStatus(i, 1);
|
||||
if(esw[0] == ESW_RELEASED && esw[1] == ESW_RELEASED) continue;
|
||||
uint8_t anybtn = 0; // any button pressed
|
||||
if(esw[0] == ESW_BUTTON || esw[1] == ESW_BUTTON){
|
||||
if(lastbtnpressed++ == 0) anybtn = 1;
|
||||
}else lastbtnpressed = 0;
|
||||
switch(curst){
|
||||
case STP_MOVE0: // move towards zero endswitch
|
||||
state[i] = STP_SLEEP;
|
||||
stp_move(i, -the_conf.maxsteps[i]); // won't move if the_conf.maxsteps == 0
|
||||
//~ write2trbuf("MOTOR");
|
||||
//~ put2trbuf('0'+i);
|
||||
//~ write2trbuf(" move0");
|
||||
//~ SENDBUF();
|
||||
break;
|
||||
case STP_MOVE1:
|
||||
state[i] = STP_SLEEP;
|
||||
stp_move(i, the_conf.maxsteps[i]);
|
||||
//~ write2trbuf("MOTOR");
|
||||
//~ put2trbuf('0'+i);
|
||||
//~ write2trbuf(" move1");
|
||||
//~ SENDBUF();
|
||||
break;
|
||||
case STP_ACCEL: // @ any move check esw
|
||||
case STP_DECEL:
|
||||
case STP_MOVE:
|
||||
case STP_MVSLOW:
|
||||
if(anybtn) state[i] = STP_STOP; // stop at the pressing moment
|
||||
else{ // check end-switches status
|
||||
if( (esw[0] == ESW_HALL && dir[i] == -1) ||
|
||||
(esw[1] == ESW_HALL && dir[i] == 1))
|
||||
case STP_MVSLOW: // check end-switches status
|
||||
if(esw[0] == ESW_HALL && dir[i] == -1){
|
||||
state[i] = STP_STOPZERO; // stop @ end-switch
|
||||
}
|
||||
break;
|
||||
case STP_SLEEP:
|
||||
if(lastbtnpressed > 30){ // one or both buttons pressed, run only after ~30ms
|
||||
if(esw[0] == ESW_BUTTON && esw[1] == ESW_BUTTON){
|
||||
// both buttons pressed
|
||||
}else{
|
||||
if(esw[0] == ESW_BUTTON) state[i] = STP_MOVE0;
|
||||
else state[i] = STP_MOVE1;
|
||||
//~ write2trbuf("MOTOR");
|
||||
//~ put2trbuf('0'+i);
|
||||
//~ write2trbuf(" stop on zero end-switch");
|
||||
//~ SENDBUF();
|
||||
}else{ if(esw[1] == ESW_HALL && dir[i] == 1){
|
||||
state[i] = STP_STOP; // stop @ end-switch 1
|
||||
//~ write2trbuf("MOTOR");
|
||||
//~ put2trbuf('0'+i);
|
||||
//~ write2trbuf(" stop on sw1");
|
||||
//~ SENDBUF();
|
||||
}
|
||||
}
|
||||
break;
|
||||
@ -134,7 +189,7 @@ void stp_process(){
|
||||
// move motor `nmotor` to `steps` steps, @return 0 if all OK
|
||||
stp_status stp_move(int nmotor, int32_t steps){
|
||||
stp_state st = state[nmotor];
|
||||
if(st != STP_SLEEP || st != STP_MOVE0 || st != STP_MOVE1) return STPS_ACTIVE;
|
||||
if(st != STP_SLEEP && st != STP_MOVE0 && st != STP_MOVE1) return STPS_ACTIVE;
|
||||
if(steps == 0)
|
||||
return STPS_ZEROMOVE;
|
||||
int8_t d;
|
||||
@ -149,33 +204,50 @@ stp_status stp_move(int nmotor, int32_t steps){
|
||||
dir[nmotor] = d;
|
||||
// change value of DIR pin
|
||||
if(the_conf.reverse[nmotor]){
|
||||
if(d)
|
||||
if(d>0)
|
||||
pin_set(MPORT[nmotor], MDIRPIN[nmotor]);
|
||||
else
|
||||
pin_clear(MPORT[nmotor], MDIRPIN[nmotor]);
|
||||
}else{
|
||||
if(d)
|
||||
if(d>0)
|
||||
pin_clear(MPORT[nmotor], MDIRPIN[nmotor]);
|
||||
else
|
||||
pin_set(MPORT[nmotor], MDIRPIN[nmotor]);
|
||||
}
|
||||
// turn on EN pin
|
||||
pin_set(MPORT[nmotor], MENPIN[nmotor]);
|
||||
// turn on EN pin (0)
|
||||
pin_clear(MPORT[nmotor], MENPIN[nmotor]);
|
||||
steps_left[nmotor] = steps;
|
||||
// setup timer & start it
|
||||
TIM_TypeDef *TIMx = nmotor ? TIM3 : TIM14;
|
||||
TIMx->ARR = stphigharr[nmotor]; // set minimal speed
|
||||
TIMx->CCR1 = stphigharr[nmotor] >> 1;
|
||||
TIMx->ARR = stphigharr[nmotor];
|
||||
TIMx->CCMR1 = TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1; // PWM mode 1: active->inacive, preload enable
|
||||
TIMx->CR1 |= TIM_CR1_CEN;
|
||||
if(steps < ACCDECSTEPS*2) state[nmotor] = STP_MVSLOW; // move without acceleration
|
||||
else state[nmotor] = STP_ACCEL; // move with acceleration
|
||||
return STPS_ALLOK;
|
||||
}
|
||||
|
||||
// change ARR and for given stepper
|
||||
void stp_chARR(int n, int32_t val){
|
||||
TIM_TypeDef *TIMx = n ? TIM3 : TIM14;
|
||||
if(val < 2) val = 2;
|
||||
TIMx->ARR = val;
|
||||
}
|
||||
|
||||
void stp_stop(int n){ // stop motor by demand or @ end-switch
|
||||
if(state[n] == STP_SLEEP) return;
|
||||
switch(state[n]){
|
||||
case STP_SLEEP:
|
||||
return;
|
||||
break;
|
||||
case STP_MOVE0:
|
||||
case STP_MOVE1:
|
||||
state[n] = STP_SLEEP;
|
||||
break;
|
||||
default:
|
||||
state[n] = STP_STOP;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// timer interrupt
|
||||
static void stpr_int(int n){
|
||||
@ -184,12 +256,13 @@ static void stpr_int(int n){
|
||||
uint16_t tmp, arrval;
|
||||
if(USTEPS == ++ustep[n]){ // prevent stop @ not full step
|
||||
ustep[n] = 0;
|
||||
if(0 == --steps_left[n]) state[n] = STP_STOP;
|
||||
if(state[n] == STP_STOPZERO)
|
||||
mot_position[n] = 0;
|
||||
else
|
||||
else{
|
||||
if(0 == --steps_left[n]) state[n] = STP_STOP;
|
||||
mot_position[n] += dir[n];
|
||||
}
|
||||
}else return;
|
||||
switch(state[n]){
|
||||
case STP_ACCEL: // acceleration phase
|
||||
arrval = TIMx->ARR - stpsteparr[n];
|
||||
@ -199,7 +272,6 @@ static void stpr_int(int n){
|
||||
state[n] = STP_MOVE; // end of acceleration phase
|
||||
}
|
||||
TIMx->ARR = arrval;
|
||||
TIMx->CCR1 = arrval >> 1;
|
||||
break;
|
||||
case STP_DECEL: // deceleration phase
|
||||
arrval = TIMx->ARR + stpsteparr[n];
|
||||
@ -209,7 +281,6 @@ static void stpr_int(int n){
|
||||
state[n] = STP_MVSLOW; // end of deceleration phase, move @ lowest speed
|
||||
}
|
||||
TIMx->ARR = arrval;
|
||||
TIMx->CCR1 = arrval >> 1;
|
||||
break;
|
||||
case STP_MOVE: // moving with constant speed phases
|
||||
if(steps_left[n] <= ACCDECSTEPS) state[n] = STP_DECEL; // change moving status to decelerate
|
||||
@ -219,8 +290,9 @@ static void stpr_int(int n){
|
||||
break;
|
||||
default: // STP_STOP, STP_STOPZERO
|
||||
ustep[n] = 0;
|
||||
TIMx->CCMR1 = TIM_CCMR1_OC1M_2; // Force inactive
|
||||
TIMx->CR1 &= ~TIM_CR1_CEN; // stop timer
|
||||
pin_clear(MPORT[n], MENPIN[n]); // turn off motor power
|
||||
pin_set(MPORT[n], MENPIN[n]); // turn off motor power
|
||||
dir[n] = 0;
|
||||
steps_left[n] = 0;
|
||||
state[n] = STP_SLEEP;
|
||||
@ -228,13 +300,13 @@ static void stpr_int(int n){
|
||||
}
|
||||
}
|
||||
|
||||
// interrupt from stepper 0 timer
|
||||
// interrupt from stepper 1 timer
|
||||
void tim3_isr(){
|
||||
stpr_int(0);
|
||||
stpr_int(1);
|
||||
TIM3->SR = 0;
|
||||
}
|
||||
// interrupt from stepper 1 timer
|
||||
// interrupt from stepper 0 timer
|
||||
void tim14_isr(){
|
||||
stpr_int(1);
|
||||
stpr_int(0);
|
||||
TIM14->SR = 0;
|
||||
}
|
||||
|
||||
@ -53,11 +53,13 @@ typedef enum{
|
||||
#define stp_position(n) (mot_position[n])
|
||||
#define stp_stepsleft(n) (steps_left[n])
|
||||
|
||||
int stp_isactive(int motnum);
|
||||
stp_state stp_getstate(int motnum);
|
||||
void stp_setup();
|
||||
void stp_chspd();
|
||||
stp_status stp_move(int nmotor, int32_t steps);
|
||||
void stp_stop(int n);
|
||||
void stp_process();
|
||||
void stp_disable();
|
||||
void stp_chARR(int n, int32_t val);
|
||||
|
||||
#endif // __STEPPERS_H__
|
||||
|
||||
@ -1,4 +1,4 @@
|
||||
update=Пн 27 ноя 2017 21:22:37
|
||||
update=Вт 12 дек 2017 11:12:17
|
||||
last_client=kicad
|
||||
[pcbnew]
|
||||
version=1
|
||||
|
||||
@ -14,6 +14,7 @@ LIBS:texas
|
||||
LIBS:transistors
|
||||
LIBS:switches
|
||||
LIBS:drv8825
|
||||
LIBS:a3212lh
|
||||
LIBS:steppers-cache
|
||||
EELAYER 25 0
|
||||
EELAYER END
|
||||
@ -1154,7 +1155,7 @@ Tim3
|
||||
Text Notes 6750 1800 0 60 ~ 0
|
||||
ADC
|
||||
Text Notes 6750 2650 0 60 ~ 0
|
||||
ADC
|
||||
Floating input
|
||||
Text Notes 6850 2450 0 60 ~ 0
|
||||
UART
|
||||
Text Notes 6700 2100 0 60 ~ 0
|
||||
@ -1713,7 +1714,7 @@ Wire Wire Line
|
||||
9500 5150 9500 5300
|
||||
Connection ~ 10200 5350
|
||||
$Comp
|
||||
L LM1117-3.3 U1
|
||||
L LM1117-3.3-RESCUE-steppers U1
|
||||
U 1 1 5A2588E7
|
||||
P 2750 5100
|
||||
F 0 "U1" H 2600 5225 50 0000 C CNN
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user