Class StepGen2 done after Stepgen.odb

This commit is contained in:
Hakan Bastedt
2024-02-08 21:28:48 +01:00
parent 2fb5252d37
commit fe3de876fa
5 changed files with 83 additions and 125 deletions

View File

@@ -7,49 +7,40 @@ class StepGen2
{
private:
volatile double_t actualPosition;
volatile double_t requestedPosition;
volatile double_t oldPosition;
volatile int32_t oldStepPosition;
volatile uint8_t enabled;
volatile int32_t nSteps;
volatile uint32_t timerPulseSteps;
volatile float Tstart;
volatile float Tstop;
volatile float Tstep;
HardwareTimer *MyTim;
HardwareTimer *MyTim2; // 10,11,13,14
int16_t stepsPerMM;
const float maxAllowedFrequency = 100000; // 100 kHz for now
HardwareTimer *pulseTimer;
uint32_t pulseTimerChan;
HardwareTimer *startTimer; // 10,11,13,14
uint8_t dirPin;
PinName stepPin;
uint32_t timerChan;
const uint32_t maxFreq = 100000;
volatile uint32_t prevFreq1 = 0;
volatile uint32_t prevFreq2 = 0;
const float Tjitter = 50.0; // Time unit is microseconds
uint32_t err = 0;
public:
static uint32_t sync0CycleTime;
volatile double_t commandedPosition; // End position when this cycle is completed
volatile int32_t commandedStepPosition; // End step position when this cycle is completed
volatile double_t initialPosition; // From previous cycle
volatile int32_t initialStepPosition; // From previous cycle
int16_t stepsPerMM; // This many steps per mm
volatile uint8_t enabled; // Enabled step generator
volatile float frequency;
static uint32_t sync0CycleTime; // Nominal EtherCAT cycle time
volatile uint32_t lcncCycleTime; // Linuxcnc nominal cycle time (1 ms often)
StepGen2(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, uint8_t _dirPin, void irq(void), TIM_TypeDef *Timer2, void irq2(void));
uint32_t handleStepper(void);
void timerCB();
void timer2CB();
void enable(uint8_t yes);
void reqPos(double_t pos) { requestedPosition = pos; };
double reqPos() { return requestedPosition; };
void oldPos(double_t pos) { oldPosition = pos; };
double oldPos() { return oldPosition; };
void oldStepPos(int32_t pos) { oldStepPosition = pos; }
int32_t oldStepPos() { return oldStepPosition; }
void actPos(double_t pos) { actualPosition = pos; };
double actPos() { return actualPosition; };
void setScale(int16_t spm) { stepsPerMM = spm; }
int16_t getScale() { return stepsPerMM; }
uint32_t updatePosAndReturn(int32_t stepPosStop, uint32_t i);
void startTimerCB();
void pulseTimerCB();
uint32_t updatePos(uint32_t i);
};
#endif