Various improvements. New pdo variable stepsPerMM.

This commit is contained in:
Hakan Bastedt
2024-01-17 00:24:17 +01:00
parent 044e8fd2c5
commit 760944afe5
9 changed files with 150 additions and 48 deletions

View File

@@ -12,5 +12,6 @@
"numeric": "cpp",
"ostream": "cpp"
},
"C_Cpp.errorSquiggles": "disabled"
"C_Cpp.errorSquiggles": "disabled",
"cmake.configureOnOpen": false
}

View File

@@ -15,21 +15,23 @@ public:
volatile double_t actualPosition;
volatile double_t requestedPosition;
HardwareTimer *MyTim;
uint32_t stepsPerMM;
uint16_t stepsPerMM;
static uint32_t sync0CycleTime;
uint8_t dirPin;
uint8_t stepPin;
uint8_t timerChan;
PinName stepPin;
uint32_t timerChan;
const uint32_t maxFreq = 100000;
volatile uint32_t prevFreq1 = 0;
volatile uint32_t prevFreq2 = 0;
StepGen(TIM_TypeDef *Timer, uint8_t timerChannel, uint8_t stepPin, uint8_t dirPin, void irq(void));
StepGen(TIM_TypeDef *Timer, uint32_t timerChannel, PinName stepPin, uint8_t dirPin, void irq(void));
void reqPos(double_t pos);
double reqPos();
void actPos(double_t pos);
double actPos();
void handleStepper(void);
void timerCB();
void setScale(int32_t spm);
void setScale(int16_t spm);
};
#endif

View File

@@ -125,7 +125,7 @@
</DataType>
<DataType>
<Name>DT1602</Name>
<BitSize>80</BitSize>
<BitSize>144</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -146,10 +146,20 @@
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1603</Name>
<BitSize>80</BitSize>
<BitSize>144</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -170,6 +180,16 @@
<Access>ro</Access>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>ULINT</Type>
<BitSize>64</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access>ro</Access>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT1A00</Name>
@@ -487,7 +507,7 @@
</DataType>
<DataType>
<Name>DT7002</Name>
<BitSize>80</BitSize>
<BitSize>96</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -509,10 +529,21 @@
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>INT</Type>
<BitSize>16</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>DT7003</Name>
<BitSize>80</BitSize>
<BitSize>96</BitSize>
<SubItem>
<SubIdx>0</SubIdx>
<Name>Max SubIndex</Name>
@@ -534,6 +565,17 @@
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
<SubItem>
<SubIdx>2</SubIdx>
<Name>StepsPerMM</Name>
<Type>INT</Type>
<BitSize>16</BitSize>
<BitOffs>80</BitOffs>
<Flags>
<Access WriteRestrictions="PreOP">ro</Access>
<PdoMapping>R</PdoMapping>
</Flags>
</SubItem>
</DataType>
<DataType>
<Name>ULINT</Name>
@@ -567,6 +609,10 @@
<Name>DINT</Name>
<BitSize>32</BitSize>
</DataType>
<DataType>
<Name>INT</Name>
<BitSize>16</BitSize>
</DataType>
</DataTypes>
<Objects>
<Object>
@@ -710,12 +756,12 @@
<Index>#x1602</Index>
<Name>StepGenIn1</Name>
<Type>DT1602</Type>
<BitSize>80</BitSize>
<BitSize>144</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -724,6 +770,12 @@
<DefaultValue>#x70020140</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>#x70020210</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -733,12 +785,12 @@
<Index>#x1603</Index>
<Name>StepGenIn2</Name>
<Type>DT1603</Type>
<BitSize>80</BitSize>
<BitSize>144</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -747,6 +799,12 @@
<DefaultValue>#x70030140</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>#x70030210</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -1195,12 +1253,12 @@
<Index>#x7002</Index>
<Name>StepGenIn1</Name>
<Type>DT7002</Type>
<BitSize>80</BitSize>
<BitSize>96</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -1209,6 +1267,12 @@
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -1218,12 +1282,12 @@
<Index>#x7003</Index>
<Name>StepGenIn2</Name>
<Type>DT7003</Type>
<BitSize>80</BitSize>
<BitSize>96</BitSize>
<Info>
<SubItem>
<Name>Max SubIndex</Name>
<Info>
<DefaultValue>1</DefaultValue>
<DefaultValue>2</DefaultValue>
</Info>
</SubItem>
<SubItem>
@@ -1232,6 +1296,12 @@
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
<SubItem>
<Name>StepsPerMM</Name>
<Info>
<DefaultValue>0</DefaultValue>
</Info>
</SubItem>
</Info>
<Flags>
<Access>ro</Access>
@@ -1279,6 +1349,13 @@
<Name>CommandedPosition</Name>
<DataType>LREAL</DataType>
</Entry>
<Entry>
<Index>#x7002</Index>
<SubIndex>#x2</SubIndex>
<BitLen>16</BitLen>
<Name>StepsPerMM</Name>
<DataType>INT</DataType>
</Entry>
</RxPdo>
<RxPdo Fixed="true" Mandatory="true" Sm="2">
<Index>#x1603</Index>
@@ -1290,6 +1367,13 @@
<Name>CommandedPosition</Name>
<DataType>LREAL</DataType>
</Entry>
<Entry>
<Index>#x7003</Index>
<SubIndex>#x2</SubIndex>
<BitLen>16</BitLen>
<Name>StepsPerMM</Name>
<DataType>INT</DataType>
</Entry>
</RxPdo>
<TxPdo Fixed="true" Mandatory="true" Sm="3">
<Index>#x1A00</Index>

View File

@@ -33,7 +33,7 @@
#define SM3_smc 0x20
#define SM3_act 1
#define MAX_MAPPINGS_SM2 4
#define MAX_MAPPINGS_SM2 6
#define MAX_MAPPINGS_SM3 7
#define MAX_RXPDO_SIZE 512

View File

@@ -183,6 +183,13 @@
"data": "&Obj.StepGenIn1.CommandedPosition",
"value": "0",
"access": "RO"
},
{
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn1.StepsPerMM"
}
],
"pdo_mappings": [
@@ -203,6 +210,13 @@
"data": "&Obj.StepGenIn2.CommandedPosition",
"value": "0",
"access": "RO"
},
{
"name": "StepsPerMM",
"dtype": "INTEGER16",
"value": "0",
"access": "RO",
"data": "&Obj.StepGenIn2.StepsPerMM"
}
],
"pdo_mappings": [

View File

@@ -22,9 +22,11 @@ static const char acName1601_01[] = "IndexLatchEnable";
static const char acName1602[] = "StepGenIn1";
static const char acName1602_00[] = "Max SubIndex";
static const char acName1602_01[] = "CommandedPosition";
static const char acName1602_02[] = "StepsPerMM";
static const char acName1603[] = "StepGenIn2";
static const char acName1603_00[] = "Max SubIndex";
static const char acName1603_01[] = "CommandedPosition";
static const char acName1603_02[] = "StepsPerMM";
static const char acName1A00[] = "EncPos";
static const char acName1A00_00[] = "Max SubIndex";
static const char acName1A00_01[] = "EncPos";
@@ -83,9 +85,11 @@ static const char acName7001[] = "IndexLatchEnable";
static const char acName7002[] = "StepGenIn1";
static const char acName7002_00[] = "Max SubIndex";
static const char acName7002_01[] = "CommandedPosition";
static const char acName7002_02[] = "StepsPerMM";
static const char acName7003[] = "StepGenIn2";
static const char acName7003_00[] = "Max SubIndex";
static const char acName7003_01[] = "CommandedPosition";
static const char acName7003_02[] = "StepsPerMM";
const _objd SDO1000[] =
{
@@ -123,13 +127,15 @@ const _objd SDO1601[] =
};
const _objd SDO1602[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 1, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1602_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_01, 0x70020140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1602_02, 0x70020210, NULL},
};
const _objd SDO1603[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 1, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName1603_00, 2, NULL},
{0x01, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_01, 0x70030140, NULL},
{0x02, DTYPE_UNSIGNED64, 64, ATYPE_RO, acName1603_02, 0x70030210, NULL},
};
const _objd SDO1A00[] =
{
@@ -233,13 +239,15 @@ const _objd SDO7001[] =
};
const _objd SDO7002[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 1, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7002_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7002_01, 0, &Obj.StepGenIn1.CommandedPosition},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7002_02, 0, &Obj.StepGenIn1.StepsPerMM},
};
const _objd SDO7003[] =
{
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7003_00, 1, NULL},
{0x00, DTYPE_UNSIGNED8, 8, ATYPE_RO, acName7003_00, 2, NULL},
{0x01, DTYPE_REAL64, 64, ATYPE_RO, acName7003_01, 0, &Obj.StepGenIn2.CommandedPosition},
{0x02, DTYPE_INTEGER16, 16, ATYPE_RO, acName7003_02, 0, &Obj.StepGenIn2.StepsPerMM},
};
const _objectlist SDOobjects[] =
@@ -251,8 +259,8 @@ const _objectlist SDOobjects[] =
{0x1018, OTYPE_RECORD, 4, 0, acName1018, SDO1018},
{0x1600, OTYPE_RECORD, 1, 0, acName1600, SDO1600},
{0x1601, OTYPE_RECORD, 1, 0, acName1601, SDO1601},
{0x1602, OTYPE_RECORD, 1, 0, acName1602, SDO1602},
{0x1603, OTYPE_RECORD, 1, 0, acName1603, SDO1603},
{0x1602, OTYPE_RECORD, 2, 0, acName1602, SDO1602},
{0x1603, OTYPE_RECORD, 2, 0, acName1603, SDO1603},
{0x1A00, OTYPE_RECORD, 1, 0, acName1A00, SDO1A00},
{0x1A01, OTYPE_RECORD, 1, 0, acName1A01, SDO1A01},
{0x1A02, OTYPE_RECORD, 1, 0, acName1A02, SDO1A02},
@@ -272,7 +280,7 @@ const _objectlist SDOobjects[] =
{0x6006, OTYPE_RECORD, 1, 0, acName6006, SDO6006},
{0x7000, OTYPE_VAR, 0, 0, acName7000, SDO7000},
{0x7001, OTYPE_VAR, 0, 0, acName7001, SDO7001},
{0x7002, OTYPE_RECORD, 1, 0, acName7002, SDO7002},
{0x7003, OTYPE_RECORD, 1, 0, acName7003, SDO7003},
{0x7002, OTYPE_RECORD, 2, 0, acName7002, SDO7002},
{0x7003, OTYPE_RECORD, 2, 0, acName7003, SDO7003},
{0xffff, 0xff, 0xff, 0xff, NULL, NULL}
};

View File

@@ -34,10 +34,12 @@ typedef struct
struct
{
double CommandedPosition;
int16_t StepsPerMM;
} StepGenIn1;
struct
{
double CommandedPosition;
int16_t StepsPerMM;
} StepGenIn2;
} _Objects;

View File

@@ -2,14 +2,13 @@
#include <stdio.h>
#include "StepGen.h"
StepGen::StepGen(TIM_TypeDef *Timer, uint8_t _timerChannel, uint8_t _stepPin, uint8_t _dirPin, void irq(void))
StepGen::StepGen(TIM_TypeDef *Timer, uint32_t _timerChannel, PinName _stepPin, uint8_t _dirPin, void irq(void))
{
timerIsRunning = 0;
timerStepPosition = 0;
timerStepDirection = 0;
timerStepPositionAtEnd = 0;
timerNewEndStepPosition = 0;
timerNewCycleTime = 0;
actualPosition = 0;
requestedPosition = 0;
stepsPerMM = 0;
@@ -18,7 +17,6 @@ StepGen::StepGen(TIM_TypeDef *Timer, uint8_t _timerChannel, uint8_t _stepPin, ui
stepPin = _stepPin;
timerChan = _timerChannel;
MyTim = new HardwareTimer(Timer);
MyTim->setMode(timerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
MyTim->attachInterrupt(irq);
pinMode(dirPin, OUTPUT);
}
@@ -52,18 +50,13 @@ void StepGen::handleStepper(void)
}
int32_t pulsesAtEndOfCycle = stepsPerMM * reqPos(); // From Turner.hal X:5000 Z:2000 ps/mm
sync0CycleTime = 1000;
// Will be picked up by the timer_CB and the timer is reloaded.
timerNewEndStepPosition = pulsesAtEndOfCycle;
if (timerIsRunning)
{
// Set variables, they will be picked up by the timer_CB and the timer is reloaded.
timerNewEndStepPosition = pulsesAtEndOfCycle;
timerNewCycleTime = sync0CycleTime;
}
if (!timerIsRunning)
if (!timerIsRunning) // no timer isn't running. start it here
{
// Start the timer
int32_t steps = pulsesAtEndOfCycle - timerStepPositionAtEnd; // Pulses to go + or -
int32_t steps = pulsesAtEndOfCycle - timerStepPosition; // Pulses to go + or -
if (steps != 0)
{
uint8_t sgn = steps > 0 ? HIGH : LOW;
@@ -83,7 +76,7 @@ void StepGen::handleStepper(void)
void StepGen::timerCB()
{
timerStepPosition += timerStepDirection; // The step that was just completed
if (timerNewCycleTime != 0) // Are we going to reload?
if (timerNewEndStepPosition != 0) // Are we going to reload?
{
// Input for reload is timerNewEndStepPosition and timerNewEndTime
// The timer has current position and current time and from this
@@ -94,12 +87,11 @@ void StepGen::timerCB()
{
uint8_t sgn = steps > 0 ? HIGH : LOW;
digitalWrite(dirPin, sgn);
double_t freqf = abs(steps) * (1e6 / double(timerNewCycleTime));
double_t freqf = abs(steps) * (1e6 / double(sync0CycleTime));
uint32_t freq = uint32_t(freqf);
timerStepDirection = steps > 0 ? 1 : -1;
timerStepPositionAtEnd = timerNewEndStepPosition;
timerNewEndStepPosition = 0; // Set to zero to not reload next time
timerNewCycleTime = 0;
MyTim->setMode(timerChan, TIMER_OUTPUT_COMPARE_PWM2, stepPin);
MyTim->setOverflow(freq, HERTZ_FORMAT);
MyTim->setCaptureCompare(timerChan, 50, PERCENT_COMPARE_FORMAT); // 50 %
@@ -114,7 +106,7 @@ void StepGen::timerCB()
}
}
void StepGen::setScale(int32_t spm)
void StepGen::setScale(int16_t spm)
{
stepsPerMM = spm;
}

View File

@@ -27,13 +27,13 @@ void indexPulseEncoderCB2(void)
#include "StepGen.h"
void timerCallbackStep1(void);
StepGen Step1(TIM1, 4, PA11, PA12, timerCallbackStep1);
StepGen Step1(TIM1, 4, PA_11, PA12, timerCallbackStep1);
void timerCallbackStep1(void)
{
Step1.timerCB();
}
void timerCallbackStep2(void);
StepGen Step2(TIM8, 4, PC9, PC10, timerCallbackStep2);
StepGen Step2(TIM8, 4, PC_9, PC10, timerCallbackStep2);
void timerCallbackStep2(void)
{
Step2.timerCB();
@@ -45,7 +45,9 @@ void cb_set_outputs(void) // Master outputs gets here, slave inputs, first opera
Encoder1.setScale(Obj.EncPosScale);
Step1.reqPos(Obj.StepGenIn1.CommandedPosition);
Step1.setScale(Obj.StepGenIn1.StepsPerMM);
Step2.reqPos(Obj.StepGenIn2.CommandedPosition);
Step2.setScale(Obj.StepGenIn2.StepsPerMM);
}
void handleStepper(void)
@@ -98,9 +100,6 @@ void setup(void)
Serial1.begin(115200);
rcc_config(); // probably breaks some timers.
Step1.setScale(1000); // 2000 /rev 4 mm/rev x 2.5 gear => 1250 /mm
Step2.setScale(500); // 2000 /rev 4 mm/rev => 500 /mm
ecat_slv_init(&config);
}