Mods to make encoder work again, and a possible 2nd iteration of encoder config
This commit is contained in:
@@ -2,7 +2,7 @@
|
|||||||
#define MYENCODER
|
#define MYENCODER
|
||||||
#include "Stm32F4_Encoder.h"
|
#include "Stm32F4_Encoder.h"
|
||||||
#include <CircularBuffer.hpp>
|
#include <CircularBuffer.hpp>
|
||||||
#define RINGBUFFERLEN 101
|
#define RINGBUFFERLEN 11
|
||||||
|
|
||||||
class MyEncoder
|
class MyEncoder
|
||||||
{
|
{
|
||||||
@@ -30,6 +30,7 @@ private:
|
|||||||
CircularBuffer<double_t, RINGBUFFERLEN> Pos;
|
CircularBuffer<double_t, RINGBUFFERLEN> Pos;
|
||||||
CircularBuffer<uint32_t, RINGBUFFERLEN> TDelta;
|
CircularBuffer<uint32_t, RINGBUFFERLEN> TDelta;
|
||||||
double curPos;
|
double curPos;
|
||||||
|
double oldFrequency;
|
||||||
|
|
||||||
TIM_TypeDef *tim_base;
|
TIM_TypeDef *tim_base;
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -641,7 +641,8 @@ public:
|
|||||||
uint16_t GetCount();
|
uint16_t GetCount();
|
||||||
};
|
};
|
||||||
|
|
||||||
void rcc_config();
|
void encoder_config();
|
||||||
|
void encoder2_config(); // Experimental
|
||||||
void GpioConfigPortA(GPIO_TypeDef *GPIOx);
|
void GpioConfigPortA(GPIO_TypeDef *GPIOx);
|
||||||
void GpioConfigPortC(GPIO_TypeDef *GPIOx);
|
void GpioConfigPortC(GPIO_TypeDef *GPIOx);
|
||||||
void GpioConfigPortD(GPIO_TypeDef *GPIOx);
|
void GpioConfigPortD(GPIO_TypeDef *GPIOx);
|
||||||
|
|||||||
@@ -61,14 +61,19 @@ double MyEncoder::frequency(uint64_t time)
|
|||||||
|
|
||||||
double diffT = 0;
|
double diffT = 0;
|
||||||
double diffPos = 0;
|
double diffPos = 0;
|
||||||
|
double frequency;
|
||||||
TDelta.push(time); // Running average over the length of the circular buffer
|
TDelta.push(time); // Running average over the length of the circular buffer
|
||||||
Pos.push(curPos);
|
Pos.push(curPos);
|
||||||
if (Pos.size() >= 2)
|
if (Pos.size() == RINGBUFFERLEN)
|
||||||
{
|
{
|
||||||
diffT = 1.0e-9 * (TDelta.last() - TDelta.first()); // Time is in nanoseconds
|
diffT = 1.0e-6 * (TDelta.last() - TDelta.first()); // Time is in microseconds
|
||||||
diffPos = fabs(Pos.last() - Pos.first());
|
diffPos = fabs(Pos.last() - Pos.first());
|
||||||
|
frequency = diffPos / diffT;
|
||||||
|
oldFrequency = frequency;
|
||||||
|
return frequency; // Revolutions per second
|
||||||
}
|
}
|
||||||
return diffT != 0 ? diffPos / diffT : 0.0; // Revolutions per second
|
else
|
||||||
|
return oldFrequency;
|
||||||
}
|
}
|
||||||
uint8_t MyEncoder::getIndexState()
|
uint8_t MyEncoder::getIndexState()
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -263,7 +263,7 @@ void GPIO_PinAF(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
|
|||||||
GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
|
GPIOx->AFR[GPIO_PinSource >> 0x03] = temp_2;
|
||||||
}
|
}
|
||||||
|
|
||||||
void rcc_config()
|
void encoder_config()
|
||||||
{
|
{
|
||||||
RCC->AHB1ENR |= 0x1; // GPIOA
|
RCC->AHB1ENR |= 0x1; // GPIOA
|
||||||
RCC->AHB1ENR |= 0x4; // GPIOC
|
RCC->AHB1ENR |= 0x4; // GPIOC
|
||||||
@@ -271,13 +271,13 @@ void rcc_config()
|
|||||||
RCC->AHB1ENR |= 0x10; // GPIOE
|
RCC->AHB1ENR |= 0x10; // GPIOE
|
||||||
|
|
||||||
RCC->APB1ENR |= 0x20000000; // ENABLE DAC
|
RCC->APB1ENR |= 0x20000000; // ENABLE DAC
|
||||||
// RCC->APB2ENR |= 0x00000002; // APB2 TIM8
|
// RCC->APB2ENR |= 0x00000002; // APB2 TIM8
|
||||||
RCC->APB1ENR |= 0x00000004; // APB1 TIM4
|
RCC->APB1ENR |= 0x00000004; // APB1 TIM4
|
||||||
RCC->APB1ENR |= 0x00000001; // APB1 TIM2
|
RCC->APB1ENR |= 0x00000001; // APB1 TIM2
|
||||||
// RCC->APB1ENR |= 0x00000002; // APB1 TIM3
|
// RCC->APB1ENR |= 0x00000002; // APB1 TIM3
|
||||||
|
|
||||||
GpioConfigPortA(GPIOA);
|
GpioConfigPortA(GPIOA);
|
||||||
// GpioConfigPortC(GPIOC);
|
// GpioConfigPortC(GPIOC);
|
||||||
GpioConfigPortD(GPIOD);
|
GpioConfigPortD(GPIOD);
|
||||||
#if 0 // Skipping since TIM8 is step generator and TIM3, chan4 is smae as TIM8, chan4
|
#if 0 // Skipping since TIM8 is step generator and TIM3, chan4 is smae as TIM8, chan4
|
||||||
GPIO_PinAF(GPIOA, GPIO_PinSource6, GPIO_AF_TIM3);
|
GPIO_PinAF(GPIOA, GPIO_PinSource6, GPIO_AF_TIM3);
|
||||||
@@ -326,4 +326,66 @@ void rcc_config()
|
|||||||
|
|
||||||
TIM3->CNT = 0;
|
TIM3->CNT = 0;
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void encoder2_config()
|
||||||
|
{
|
||||||
|
#if 0
|
||||||
|
#include "mbed.h"
|
||||||
|
#include "stm32f4xx.h"
|
||||||
|
#include "stm32f4xx_hal_tim_ex.h"
|
||||||
|
|
||||||
|
TIM_HandleTypeDef timer;
|
||||||
|
TIM_Encoder_InitTypeDef encoder;
|
||||||
|
|
||||||
|
// direction to PA_9 -- step pulse to PA_8
|
||||||
|
|
||||||
|
int main()
|
||||||
|
{
|
||||||
|
|
||||||
|
GPIO_InitTypeDef GPIO_InitStruct;
|
||||||
|
__TIM1_CLK_ENABLE();
|
||||||
|
__GPIOA_CLK_ENABLE();
|
||||||
|
GPIO_InitStruct.Pin = GPIO_PIN_8 | GPIO_PIN_9;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_HIGH;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF1_TIM1;
|
||||||
|
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
timer.Instance = TIM1;
|
||||||
|
timer.Init.Period = 0xffff;
|
||||||
|
timer.Init.Prescaler = 0;
|
||||||
|
timer.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
|
timer.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
|
||||||
|
encoder.EncoderMode = TIM_ENCODERMODE_TI12;
|
||||||
|
encoder.IC1Filter = 0x0f;
|
||||||
|
encoder.IC1Polarity = TIM_INPUTCHANNELPOLARITY_RISING;
|
||||||
|
encoder.IC1Prescaler = TIM_ICPSC_DIV4;
|
||||||
|
encoder.IC1Selection = TIM_ICSELECTION_DIRECTTI;
|
||||||
|
|
||||||
|
encoder.IC2Filter = 0x0f;
|
||||||
|
encoder.IC2Polarity = TIM_INPUTCHANNELPOLARITY_FALLING;
|
||||||
|
encoder.IC2Prescaler = TIM_ICPSC_DIV4;
|
||||||
|
encoder.IC2Selection = TIM_ICSELECTION_DIRECTTI;
|
||||||
|
|
||||||
|
HAL_TIM_Encoder_Init(&timer, &encoder);
|
||||||
|
HAL_TIM_Encoder_Start(&timer,TIM_CHANNEL_1);
|
||||||
|
|
||||||
|
|
||||||
|
TIM1->EGR = 1; // Generate an update event
|
||||||
|
TIM1->CR1 = 1; // Enable the counter
|
||||||
|
|
||||||
|
|
||||||
|
while (1) {
|
||||||
|
int16_t count1;
|
||||||
|
count1=TIM1->CNT;
|
||||||
|
|
||||||
|
printf("%d\r\n", count1);
|
||||||
|
wait(1.0);
|
||||||
|
|
||||||
|
};
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
@@ -15,10 +15,12 @@ HardwareTimer *syncTimer; // The timer that syncs "with linuxcnc cycle"
|
|||||||
uint16_t sync0CycleTime; // usecs
|
uint16_t sync0CycleTime; // usecs
|
||||||
|
|
||||||
#include "MyEncoder.h"
|
#include "MyEncoder.h"
|
||||||
|
volatile uint16_t encCnt = 0;
|
||||||
void indexPulseEncoderCB1(void);
|
void indexPulseEncoderCB1(void);
|
||||||
MyEncoder Encoder1(TIM2, PA2, indexPulseEncoderCB1);
|
MyEncoder Encoder1(TIM2, PA2, indexPulseEncoderCB1);
|
||||||
void indexPulseEncoderCB1(void)
|
void indexPulseEncoderCB1(void)
|
||||||
{
|
{
|
||||||
|
encCnt++;
|
||||||
Encoder1.indexPulse();
|
Encoder1.indexPulse();
|
||||||
}
|
}
|
||||||
#include <RunningAverage.h>
|
#include <RunningAverage.h>
|
||||||
@@ -120,13 +122,13 @@ void cb_get_inputs(void) // Set Master inputs, slave outputs, last operation
|
|||||||
{
|
{
|
||||||
Obj.IndexStatus = Encoder1.indexHappened();
|
Obj.IndexStatus = Encoder1.indexHappened();
|
||||||
Obj.EncPos = Encoder1.currentPos();
|
Obj.EncPos = Encoder1.currentPos();
|
||||||
Obj.EncFrequency = Encoder1.frequency(ESCvar.Time);
|
Obj.EncFrequency = Encoder1.frequency(longTime.extendTime(micros()));
|
||||||
Obj.IndexByte = Encoder1.getIndexState();
|
Obj.IndexByte = Encoder1.getIndexState();
|
||||||
|
|
||||||
Obj.DiffT = nLoops;
|
Obj.DiffT = nLoops;
|
||||||
Obj.D1 = 1000 * Obj.CommandedPosition2; // abs(1000 * (ap2 - Obj.CommandedPosition2)); // Step2.actPos();
|
Obj.D1 = 1000 * Obj.CommandedPosition2; // abs(1000 * (ap2 - Obj.CommandedPosition2)); // Step2.actPos();
|
||||||
Obj.D2 = 1000 * Obj.ActualPosition2; // Step->stepgen_array[1].pos_fb; // Step->stepgen_array[1].rawcount % INT16_MAX; // Step->stepgen_array[1].freq;
|
Obj.D2 = 1000 * Obj.ActualPosition2; // Step->stepgen_array[1].pos_fb; // Step->stepgen_array[1].rawcount % INT16_MAX; // Step->stepgen_array[1].freq;
|
||||||
Obj.D3 = irqCnt % 256; // Step->stepgen_array[1].freq;
|
Obj.D3 = encCnt % 256; // Step->stepgen_array[1].freq;
|
||||||
Obj.D4 = 1000 * (Obj.CommandedPosition2 - oldCommandedPosition); // deltaMakePulsesCnt; // Step->stepgen_array[1].rawcount % UINT16_MAX;
|
Obj.D4 = 1000 * (Obj.CommandedPosition2 - oldCommandedPosition); // deltaMakePulsesCnt; // Step->stepgen_array[1].rawcount % UINT16_MAX;
|
||||||
oldCommandedPosition = Obj.CommandedPosition2;
|
oldCommandedPosition = Obj.CommandedPosition2;
|
||||||
}
|
}
|
||||||
@@ -166,7 +168,9 @@ void setup(void)
|
|||||||
#if 0
|
#if 0
|
||||||
measureCrystalFrequency(); // Calibrate crystal frequency
|
measureCrystalFrequency(); // Calibrate crystal frequency
|
||||||
#endif
|
#endif
|
||||||
rcc_config(); // Needed by encoder, probably breaks some timers.
|
Step = new StepGen3;
|
||||||
|
|
||||||
|
encoder_config(); // Needed by encoder, probably breaks some timers.
|
||||||
ecat_slv_init(&config);
|
ecat_slv_init(&config);
|
||||||
|
|
||||||
pinMode(PA11, OUTPUT); // Step X
|
pinMode(PA11, OUTPUT); // Step X
|
||||||
@@ -174,7 +178,7 @@ void setup(void)
|
|||||||
pinMode(PC9, OUTPUT); // Step Z
|
pinMode(PC9, OUTPUT); // Step Z
|
||||||
pinMode(PC10, OUTPUT); // Dir Z
|
pinMode(PC10, OUTPUT); // Dir Z
|
||||||
|
|
||||||
Step = new StepGen3;
|
|
||||||
|
|
||||||
baseTimer = new HardwareTimer(TIM11); // The base period timer
|
baseTimer = new HardwareTimer(TIM11); // The base period timer
|
||||||
setFrequencyAdjustedMicrosSeconds(baseTimer, BASE_PERIOD / 1000);
|
setFrequencyAdjustedMicrosSeconds(baseTimer, BASE_PERIOD / 1000);
|
||||||
|
|||||||
@@ -10,5 +10,12 @@ license "GPL";
|
|||||||
//main function
|
//main function
|
||||||
FUNCTION(_) {
|
FUNCTION(_) {
|
||||||
index_latch_enable = index_c_enable;
|
index_latch_enable = index_c_enable;
|
||||||
index_c_enable = index_status;
|
if (index_latch_enable) {
|
||||||
|
if (index_status) {
|
||||||
|
index_c_enable = 0;
|
||||||
|
}
|
||||||
|
// else wait for index-status
|
||||||
|
} else {
|
||||||
|
index_c_enable = index_status;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user