beginning of work with steppers (NOT TESTED!)

This commit is contained in:
eddyem 2017-12-07 21:18:59 +03:00
parent 1210df589e
commit 025d323135
10 changed files with 485 additions and 28 deletions

View File

@ -200,8 +200,8 @@ TRUE_INLINE void StartHSI48(){
/************************* ADC *************************/
/* inner termometer calibration values
* Temp = (Vsense - V30)/Avg_Slope + 30
* Avg_Slope = (V110 - V30) / (110 - 30)
* Temp = (V30 - Vsense)/Avg_Slope + 30
* Avg_Slope = (V30 - V110) / (110 - 30)
*/
#define TEMP110_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7C2))
#define TEMP30_CAL_ADDR ((uint16_t*) ((uint32_t) 0x1FFFF7B8))
@ -216,6 +216,12 @@ TRUE_INLINE void StartHSI48(){
// set address/character match value
#define USART_CR2_ADD_VAL(x) ((x) << USART_CR2_ADD_SHIFT)
/************************* IWDG *************************/
#define IWDG_REFRESH (uint32_t)(0x0000AAAA)
#define IWDG_WRITE_ACCESS (uint32_t)(0x00005555)
#define IWDG_START (uint32_t)(0x0000CCCC)
//#define do{}while(0)

View File

@ -25,6 +25,12 @@
#include "adc.h"
#include "usart.h"
extern volatile uint32_t Tms; // time counter for 1-second Vdd measurement
static uint32_t lastVddtime = 0; // Tms value of last Vdd measurement
static uint32_t VddValue = 0; // value of Vdd * 100 (for more precision measurements)
// check time of last Vdd measurement & refresh it value
#define CHKVDDTIME() do{if(!VddValue || Tms < lastVddtime || Tms - lastVddtime > 999) getVdd();}while(0)
/*
* 0 - Steppers current
* 1 - Input voltage 12V
@ -91,7 +97,9 @@ void adc_setup(){
// return MCU temperature (degrees of celsius)
int32_t getTemp(){
int32_t temperature = (int32_t)ADC_array[6];
CHKVDDTIME();
// make correction on Vdd value
int32_t temperature = (int32_t)ADC_array[6] * VddValue / 330;
write2trbuf("getTemp()\ncal30=");
put_uint(*TEMP30_CAL_ADDR);
write2trbuf(", cal110=");
@ -99,7 +107,7 @@ put_uint(*TEMP110_CAL_ADDR);
write2trbuf(", t=");
put_int(temperature);
SENDBUF();
temperature = ((int32_t) *TEMP30_CAL_ADDR - temperature);
temperature = (int32_t) *TEMP30_CAL_ADDR - temperature;
put_int(temperature);
SENDBUF();
temperature *= (int32_t)(1100 - 300);
@ -115,28 +123,59 @@ SENDBUF();
//static uint32_t calval = 0;
// return Vdd * 10 (V)
uint32_t getVdd(){
#define ARRSZ (10)
static uint16_t arr[ARRSZ] = {0};
static int arridx = 0;
uint32_t v = ADC_array[7];
int i;
write2trbuf("getVdd(), val=");
put_uint(ADC_array[7]);
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)33 * the_conf.v33numerator; // 3.3V
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 /= ADC_array[7] * the_conf.v33denominator;
vdd /= v * the_conf.v33denominator;
put_uint(vdd);
SENDBUF();
return vdd;
lastVddtime = Tms;
VddValue = vdd;
return vdd/10;
}
// return value of 12V * 10 (V)
uint32_t getVmot(){
uint32_t vmot = ADC_array[1] * getVdd() * the_conf.v12numerator;
CHKVDDTIME();
uint32_t vmot = ADC_array[1] * VddValue * the_conf.v12numerator;
vmot >>= 12;
vmot /= the_conf.v12denominator;
return vmot;
@ -144,7 +183,8 @@ uint32_t getVmot(){
// return value of motors' current * 100 (A)
uint32_t getImot(){
uint32_t vmot = ADC_array[0] * getVdd() * the_conf.i12numerator * 10;
CHKVDDTIME();
uint32_t vmot = ADC_array[0] * VddValue * the_conf.i12numerator;
vmot >>= 12;
vmot /= the_conf.i12denominator;
return vmot;

View File

@ -30,16 +30,21 @@
#define FLASH_CONF_START_ADDR ((uint32_t)0x08003C00)
static const int maxnum = 1024 / sizeof(user_conf);
// all denominators except Vdd by default are 10 (as Vdd stored as V*100, other data as V*10)
user_conf the_conf = {
.userconf_sz = sizeof(user_conf)
,.devID = 0
,.v12numerator = 1
,.v12denominator = 1
,.v12denominator = 10
,.i12numerator = 1
,.i12denominator = 1
,.v33denominator = 1
,.v33numerator = 1
,.ESW_thres = 150
,.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
,.reverse = {0,0} // set DIR to this value when moving to '+'
};
static int erase_flash();

View File

@ -36,6 +36,10 @@ typedef struct{
uint16_t i12denominator;
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 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;
extern user_conf the_conf;

View File

@ -24,6 +24,7 @@
#include "adc.h"
#include "flash.h"
#include "proto.h"
#include "steppers.h"
volatile uint32_t Tms = 0;
@ -59,6 +60,28 @@ static void gpio_setup(void){
GPIOF->MODER = GPIO_MODER_MODER0_O | GPIO_MODER_MODER1_O;
}
void iwdg_setup(){
/* Enable the peripheral clock RTC */
/* (1) Enable the LSI (40kHz) */
/* (2) Wait while it is not ready */
RCC->CSR |= RCC_CSR_LSION; /* (1) */
while((RCC->CSR & RCC_CSR_LSIRDY) != RCC_CSR_LSIRDY); /* (2) */
/* Configure IWDG */
/* (1) Activate IWDG (not needed if done in option bytes) */
/* (2) Enable write access to IWDG registers */
/* (3) Set prescaler by 64 (1.6ms for each tick) */
/* (4) Set reload value to have a rollover each 2s */
/* (5) Check if flags are reset */
/* (6) Refresh counter */
IWDG->KR = IWDG_START; /* (1) */
IWDG->KR = IWDG_WRITE_ACCESS; /* (2) */
IWDG->PR = IWDG_PR_PR_1; /* (3) */
IWDG->RLR = 1250; /* (4) */
while(IWDG->SR); /* (5) */
IWDG->KR = IWDG_REFRESH; /* (6) */
}
int main(void){
uint32_t lastT = 0;
uint32_t ostctr = 0;
@ -69,12 +92,15 @@ int main(void){
char *txt = NULL;
sysreset();
SysTick_Config(6000, 1);
get_userconf();
gpio_setup();
adc_setup();
USART1_config();
get_userconf();
stp_setup();
iwdg_setup();
//pin_set(GPIOA, 1<<5); // clear extern LED
while (1){
IWDG->KR = IWDG_REFRESH; // refresh watchdog
if(lastT > Tms || Tms - lastT > 499){
#ifdef EBUG
pin_toggle(GPIOA, 1<<4); // blink by onboard LED once per second
@ -93,19 +119,20 @@ int main(void){
txt = "hello";
}
#endif
/*
if(trbufisfull()){
write2trbuf("ERR");
usart1_send_blocking(gettrbuf());
}
cleartrbuf();
cleartrbuf();*/
if(txt){ // text waits for sending
if(ALL_OK == usart1_send(txt)){
txt = NULL;
}
}
if(ostctr != Tms){
if(ostctr != Tms){ // check steppers not frequently than once in 1ms
ostctr = Tms;
//
stp_process();
}
}
}

View File

@ -26,6 +26,7 @@
#include "flash.h"
#include "string.h"
#include "usart.h"
#include "steppers.h"
static const char *eodata = "DATAEND";
static const char *badcmd = "BADCMD";
@ -40,14 +41,18 @@ 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 *get_status();
static char *get_conf();
static char *get_raw_adc();
static char *get_ADCval(char *str);
static char *get_temper();
static char *setDenEn(uint8_t De, char *str);
static char *setDevId(char *str);
static char *setESWthres(char *str);
static char *get_temper();
static char *setUSARTspd(char *str);
#define omitwsp(str) do{register char nxt; while((nxt = *str)){if(nxt != ' ' && nxt != '\t') break; else ++str;}}while(0)
@ -70,12 +75,15 @@ char* process_command(char *cmdbuf){
return "ALIVE";
}
switch (*str++){
case 'S': // set something
return set_something(str);
break;
case 'G': // get something
return get_something(str);
break;
case 'R':
NVIC_SystemReset();
break;
case 'S': // set something
return set_something(str);
break;
case 'W': // write flash
if(store_userconf()) return ERR;
else return ALLOK;
@ -136,7 +144,7 @@ static char *get_something(char *str){
case 'R': // get raw ADC values
return get_raw_adc();
break;
case 'S': // get status
case 'S': // get motors' status
return get_status();
break;
case 'T':
@ -147,6 +155,49 @@ static char *get_something(char *str){
}
static char *get_status(){
int i, j;
char str[3] = {0, '=', 0};
if(RCC->CSR & RCC_CSR_IWDGRSTF){ // watchdog reset occured
write2trbuf("WDGRESET=1");
}
if(RCC->CSR & RCC_CSR_SFTRSTF){ // software reset occured
write2trbuf("SOFTRESET=1");
}
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");
write2trbuf(str);
put_uint(stp_stepsleft(i));
}else write2trbuf("STOP");
write2trbuf("POS");
write2trbuf(str);
put_int(stp_position(i));
SENDBUF();
for(j = 0; j < 2; ++j){
write2trbuf("ESW"); put2trbuf('0' + i);
put2trbuf('0' + j); put2trbuf('=');
ESW_status stat = eswStatus(i, j);
const char *etxt = "ERR";
switch(stat){
case ESW_RELEASED:
etxt = "RLSD";
break;
case ESW_BUTTON:
etxt = "BTN";
break;
case ESW_HALL:
etxt = "HALL";
break;
default:
break;
}
write2trbuf(etxt);
SENDBUF();
}
}
return NULL;
}
@ -165,6 +216,8 @@ static const user_conf_descr descrarr[] = {
{"V33NUM", &the_conf.v33numerator},
{"V33DEN", &the_conf.v33denominator},
{"ESWTHR", &the_conf.ESW_thres},
{"MOT0SPD",&the_conf.motspd[0]},
{"MOT1SPD",&the_conf.motspd[1]},
{NULL, NULL}
};
@ -176,6 +229,13 @@ static char *get_conf(){
put_uint((uint32_t) *curdesc->ptr);
SENDBUF();
}while((++curdesc)->fieldname);
write2trbuf("USARTSPD=");
put_uint(the_conf.usartspd);
SENDBUF();
write2trbuf("REVERSE0=");
put_uint(the_conf.reverse[0]);
write2trbuf("\nREVERSE1=");
put_uint(the_conf.reverse[1]);
return EODATA;
}
@ -214,6 +274,14 @@ static char *get_ADCval(char *str){
return NULL;
}
static char *get_temper(){
int32_t t = getTemp();
write2trbuf("TEMP=");
put_int(t);
SENDBUF();
return NULL;
}
static char *set_something(char *str){
switch(*str++){
case 'D': // set denominator
@ -228,6 +296,9 @@ static char *set_something(char *str){
case 'T': // set endsw threshold
return setESWthres(str);
break;
case 'U': // set USART speed
return setUSARTspd(str);
break;
}
return BADCMD;
}
@ -269,10 +340,10 @@ static char *setESWthres(char *str){
return ALLOK;
}
static char *get_temper(){
int32_t t = getTemp();
write2trbuf("TEMP=");
put_int(t);
SENDBUF();
return NULL;
static char *setUSARTspd(char *str){
omitwsp(str);
int32_t N32;
if(!getnum(str, &N32)) return BADCMD;
the_conf.usartspd = (uint32_t) N32;
return ALLOK;
}

Binary file not shown.

240
STM32/steppers/steppers.c Normal file
View File

@ -0,0 +1,240 @@
/*
* geany_encoding=koi8-r
* steppers.c
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#include "steppers.h"
#include "flash.h"
#include "adc.h"
// amount of steps need for full acceleration/deceleration cycle
#define ACCDECSTEPS (50)
// amount of microsteps in each step
#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
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
static stp_state state[2] = {STP_SLEEP, STP_SLEEP}; // current state of motor
// ARR register values: low (max speed), high (min speed = 10% from max), step (1/50(hi-lo))
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;
}
void stp_chspd(){
int i;
for(i = 0; i < 2; ++i){
uint16_t spd = the_conf.motspd[i] << 4;
if(spd && spd < 6553){
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->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;
TIM14->PSC = 999;
TIM14->CCER = TIM_CCER_CC1P | TIM_CCER_CC1E;
TIM14->DIER = TIM_DIER_UIE;
// enable IRQ
NVIC_EnableIRQ(TIM3_IRQn);
NVIC_SetPriority(TIM3_IRQn, 0);
NVIC_EnableIRQ(TIM14_IRQn);
NVIC_SetPriority(TIM14_IRQn, 0);
}
// setup timers
void stp_setup(){
timers_setup();
stp_chspd();
}
// 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];
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
stp_move(i, -the_conf.maxsteps[i]); // won't move if the_conf.maxsteps == 0
break;
case STP_MOVE1:
stp_move(i, the_conf.maxsteps[i]);
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))
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;
}
}
break;
default: // stopping states - do nothing
break;
}
}
}
// 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(steps == 0)
return STPS_ZEROMOVE;
int8_t d;
if(steps < 0){
d = -1;
steps = -steps;
}else d = 1; // positive direction
if(the_conf.maxsteps[nmotor] && steps > the_conf.maxsteps[nmotor]) return STPS_TOOBIG;
// check end-switches
if(eswStatus(nmotor, 0) == ESW_HALL && d == -1) return STPS_ONESW;
if(eswStatus(nmotor, 1) == ESW_HALL && d == 1) return STPS_ONESW;
dir[nmotor] = d;
// change value of DIR pin
if(the_conf.reverse[nmotor]){
if(d)
pin_set(MPORT[nmotor], MDIRPIN[nmotor]);
else
pin_clear(MPORT[nmotor], MDIRPIN[nmotor]);
}else{
if(d)
pin_clear(MPORT[nmotor], MDIRPIN[nmotor]);
else
pin_set(MPORT[nmotor], MDIRPIN[nmotor]);
}
// turn on EN pin
pin_set(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->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;
}
void stp_stop(int n){ // stop motor by demand or @ end-switch
if(state[n] == STP_SLEEP) return;
state[n] = STP_STOP;
}
// timer interrupt
static void stpr_int(int n){
static uint8_t ustep[2] = {0,0};
TIM_TypeDef *TIMx = n ? TIM3 : TIM14;
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
mot_position[n] += dir[n];
}
switch(state[n]){
case STP_ACCEL: // acceleration phase
arrval = TIMx->ARR - stpsteparr[n];
tmp = stplowarr[n];
if(arrval <= tmp || arrval > stphigharr[n]){
arrval = tmp;
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];
tmp = stphigharr[n];
if(arrval >= tmp || arrval < stplowarr[n]){
arrval = tmp;
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
break;
case STP_MVSLOW:
// nothing to do here: all done before switch()
break;
default: // STP_STOP, STP_STOPZERO
ustep[n] = 0;
TIMx->CR1 &= ~TIM_CR1_CEN; // stop timer
pin_clear(MPORT[n], MENPIN[n]); // turn off motor power
dir[n] = 0;
steps_left[n] = 0;
state[n] = STP_SLEEP;
break;
}
}
// interrupt from stepper 0 timer
void tim3_isr(){
stpr_int(0);
TIM3->SR = 0;
}
// interrupt from stepper 1 timer
void tim14_isr(){
stpr_int(1);
TIM14->SR = 0;
}

63
STM32/steppers/steppers.h Normal file
View File

@ -0,0 +1,63 @@
/*
* geany_encoding=koi8-r
* steppers.h
*
* Copyright 2017 Edward V. Emelianov <eddy@sao.ru, edward.emelianoff@gmail.com>
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
* MA 02110-1301, USA.
*
*/
#pragma once
#ifndef __STEPPERS_H__
#define __STEPPERS_H__
#include "stm32f0.h"
extern int32_t mot_position[];
extern uint32_t steps_left[];
// stepper states
typedef enum{
STP_SLEEP, // don't moving
STP_ACCEL, // start moving with acceleration
STP_MOVE, // moving with constant speed
STP_MVSLOW, // moving with slowest constant speed
STP_DECEL, // moving with deceleration
STP_STOP, // stop motor right now (by demand)
STP_STOPZERO, // stop motor and zero its position (on end-switch)
STP_MOVE0, // move towards 0 endswitch (negative direction)
STP_MOVE1, // move towards 1 endswitch (positive direction)
} stp_state;
typedef enum{
STPS_ALLOK, // no errors
STPS_ACTIVE, // motor is still moving
STPS_TOOBIG, // amount of steps too big
STPS_ZEROMOVE, // give 0 steps to move
STPS_ONESW // staying on end-switch & try to move further
} stp_status;
#define stp_position(n) (mot_position[n])
#define stp_stepsleft(n) (steps_left[n])
int stp_isactive(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();
#endif // __STEPPERS_H__

View File

@ -20,6 +20,7 @@
*/
#include "usart.h"
#include "flash.h"
#include <string.h> // memcpy
extern volatile uint32_t Tms;
@ -77,9 +78,9 @@ void USART1_config(){
/* Enable the peripheral clock USART1 */
RCC->APB2ENR |= RCC_APB2ENR_USART1EN;
/* Configure USART1 */
/* (1) oversampling by 16, 115200 baud */
/* (1) oversampling by 16, set speed */
/* (2) 8 data bit, 1 start bit, 1 stop bit, no parity */
USART1->BRR = 480000 / 1152; /* (1) */
USART1->BRR = 48000000 / the_conf.usartspd; /* (1) */
USART1->CR1 = USART_CR1_TE | USART_CR1_RE | USART_CR1_UE; /* (2) */
/* polling idle frame Transmission */
while(!(USART1->ISR & USART_ISR_TC)){}