Skip to content

Commit 70a0498

Browse files
committed
Merge branch 'hotfix/GCC9_Compatibility'
2 parents f3e6b6f + bc65ad5 commit 70a0498

8 files changed

+60
-60
lines changed

src/RotateControlBase.h

+18-18
Original file line numberDiff line numberDiff line change
@@ -1,19 +1,19 @@
11
#pragma once
22

33
#include "MotorControlBase.h"
4-
#include <algorithm>
4+
//#include <algorithm>
55
#include "core_pins.h"
66

77
template <typename Accelerator, typename TimerField>
88
class RotateControlBase : public MotorControlBase<TimerField>
99
{
1010
public:
11-
RotateControlBase(unsigned pulseWidth = 5, unsigned accUpdatePeriod = 5000);
11+
RotateControlBase(unsigned pulseWidth = 5, unsigned accUpdatePeriod = 5000);
1212

1313
// Non-blocking movements ----------------
1414
template <typename... Steppers>
1515
void rotateAsync(Steppers &... steppers);
16-
16+
1717
template <size_t N>
1818
void rotateAsync(Stepper *(&motors)[N]);
1919

@@ -59,33 +59,33 @@ void RotateControlBase<a, t>::doRotate(int N, float speedFactor)
5959
if (this->leadMotor->vMax == 0)
6060
return;
6161

62-
this->leadMotor->currentSpeed = 0;
62+
this->leadMotor->currentSpeed = 0;
6363

64-
this->leadMotor->A = std::abs(this->leadMotor->vMax);
64+
this->leadMotor->A = abs(this->leadMotor->vMax);
6565
for (int i = 1; i < N; i++)
6666
{
67-
this->motorList[i]->A = std::abs(this->motorList[i]->vMax);
67+
this->motorList[i]->A = abs(this->motorList[i]->vMax);
6868
this->motorList[i]->B = 2 * this->motorList[i]->A - this->leadMotor->A;
6969
}
7070
uint32_t acceleration = (*std::min_element(this->motorList, this->motorList + N, Stepper::cmpAcc))->a; // use the lowest acceleration for the move
71-
72-
// Start moving---------------------------------------------------------------------------------------
71+
72+
// Start moving---------------------------------------------------------------------------------------
7373
accelerator.prepareRotation(this->leadMotor->current, this->leadMotor->vMax, acceleration, this->accUpdatePeriod, speedFactor);
74-
this->timerField.setStepFrequency(0);
75-
this->timerField.accTimerStart();
74+
this->timerField.setStepFrequency(0);
75+
this->timerField.accTimerStart();
7676
}
7777

7878
// ISR -----------------------------------------------------------------------------------------------------------
7979

8080
template <typename a, typename t>
8181
void RotateControlBase<a, t>::accTimerISR()
82-
{
82+
{
8383
int32_t newSpeed = accelerator.updateSpeed(this->leadMotor->current); // get new speed for the leading motor
84-
84+
8585
//Serial.printf("rc,curSpeed: %i newspd:%i\n",this->leadMotor->currentSpeed, newSpeed);
8686

8787
if (this->leadMotor->currentSpeed == newSpeed)
88-
{
88+
{
8989
return; // nothing changed, just keep running
9090
}
9191

@@ -99,10 +99,10 @@ void RotateControlBase<a, t>::accTimerISR()
9999
}
100100
delayMicroseconds(this->pulseWidth);
101101
}
102-
103-
104-
this->timerField.setStepFrequency(std::abs(newSpeed)); // speed changed, update timer
105-
this->leadMotor->currentSpeed = newSpeed;
102+
103+
104+
this->timerField.setStepFrequency(abs(newSpeed)); // speed changed, update timer
105+
this->leadMotor->currentSpeed = newSpeed;
106106
}
107107

108108
// ROTATE Commands -------------------------------------------------------------------------------
@@ -117,7 +117,7 @@ void RotateControlBase<a, t>::rotateAsync(Steppers &... steppers)
117117

118118
template <typename a, typename t>
119119
template <size_t N>
120-
void RotateControlBase<a, t>::rotateAsync(Stepper *(&steppers)[N])
120+
void RotateControlBase<a, t>::rotateAsync(Stepper *(&steppers)[N])
121121
{
122122
this->attachStepper(steppers);
123123
doRotate(N);

src/StepControlBase.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ void StepControlBase<a, t>::doMove(int N, bool move)
6161
}
6262

6363
// Calculate acceleration parameters --------------------------------------------------------------
64-
uint32_t targetSpeed = std::abs((*std::min_element(this->motorList, this->motorList + N, Stepper::cmpVmin))->vMax); // use the lowest max frequency for the move, scale by relSpeed
64+
uint32_t targetSpeed = abs((*std::min_element(this->motorList, this->motorList + N, Stepper::cmpVmin))->vMax); // use the lowest max frequency for the move, scale by relSpeed
6565
uint32_t acceleration = (*std::min_element(this->motorList, this->motorList + N, Stepper::cmpAcc))->a; // use the lowest acceleration for the move
6666
if (this->leadMotor->A == 0 || targetSpeed == 0)
6767
return;

src/Stepper.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -78,4 +78,9 @@ void Stepper::setTargetRel(int32_t delta)
7878
setDir(delta < 0 ? -1 : 1);
7979
target = current + delta;
8080
A = std::abs(delta);
81-
}
81+
}
82+
83+
const int32_t Stepper::vMaxMax = 300000; // largest speed possible (steps/s)
84+
const uint32_t Stepper::aMax = 500000; // speed up to 500kHz within 1 s (steps/s^2)
85+
const uint32_t Stepper::vMaxDefault = 800; // should work with every motor (1 rev/sec in 1/4-step mode)
86+
const uint32_t Stepper::aDefault = 2500; // reasonably low (~0.5s for reaching the default speed)

src/Stepper.h

+7-7
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,10 @@
55

66
class Stepper
77
{
8-
static constexpr int32_t vMaxMax = 300000; // largest speed possible (steps/s)
9-
static constexpr uint32_t aMax = 500000; // speed up to 500kHz within 1 s (steps/s^2)
10-
static constexpr uint32_t vMaxDefault = 800; // should work with every motor (1 rev/sec in 1/4-step mode)
11-
static constexpr uint32_t aDefault = 2500; // reasonably low (~0.5s for reaching the default speed)
8+
static const int32_t vMaxMax; // largest speed possible (steps/s)
9+
static const uint32_t aMax; // speed up to 500kHz within 1 s (steps/s^2)
10+
static const uint32_t vMaxDefault; // should work with every motor (1 rev/sec in 1/4-step mode)
11+
static const uint32_t aDefault; // reasonably low (~0.5s for reaching the default speed)
1212

1313
public:
1414
Stepper(const int StepPin, const int DirPin);
@@ -34,7 +34,7 @@ class Stepper
3434
inline void toggleDir();
3535

3636
volatile int32_t current;
37-
volatile int32_t currentSpeed;
37+
volatile int32_t currentSpeed;
3838
volatile int32_t target;
3939

4040
int32_t A, B; // Bresenham paramters
@@ -44,8 +44,8 @@ class Stepper
4444
// compare functions
4545
static bool cmpDelta(const Stepper *a, const Stepper *b) { return a->A > b->A; }
4646
static bool cmpAcc(const Stepper *a, const Stepper *b) { return a->a < b->a; }
47-
static bool cmpVmin(const Stepper *a, const Stepper *b) { return std::abs(a->vMax) < std::abs(b->vMax); }
48-
static bool cmpVmax(const Stepper *a, const Stepper *b) { return std::abs(a->vMax) > std::abs(b->vMax); }
47+
static bool cmpVmin(const Stepper *a, const Stepper *b) { return abs(a->vMax) < abs(b->vMax); }
48+
static bool cmpVmax(const Stepper *a, const Stepper *b) { return abs(a->vMax) > abs(b->vMax); }
4949

5050
// Pin & Dir registers
5151
volatile uint32_t *stepPinActiveReg;

src/TeensyStep.h

-2
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,5 @@
11
#pragma once
22

3-
#include "version.h"
4-
53
#include "RotateControlBase.h"
64
#include "StepControlBase.h"
75

src/accelerators/LinRotAccelerator.h

+4-7
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,8 @@
11
#pragma once
22

3-
#include "wiring.h"
43

5-
#include <cmath>
6-
#include <cstdint>
7-
#include <algorithm>
4+
#include "Arduino.h"
5+
86

97
class LinRotAccelerator
108
{
@@ -34,7 +32,7 @@ class LinRotAccelerator
3432
void LinRotAccelerator::prepareRotation(int32_t currentPosition, int32_t targetSpeed, uint32_t a, uint32_t accUpdatePeriod, float speedFactor)
3533
{
3634
v_tgt_orig = targetSpeed;
37-
dv_orig = ((float)a * accUpdatePeriod) / 1E6;
35+
dv_orig = ((float)a * accUpdatePeriod) / 1E6;
3836
v_cur = 0;
3937

4038
overrideAcceleration(1.0f);
@@ -44,7 +42,7 @@ void LinRotAccelerator::prepareRotation(int32_t currentPosition, int32_t targetS
4442
void LinRotAccelerator::overrideSpeed(float factor)
4543
{
4644
//Serial.printf("a:------ %d\n", a);
47-
45+
4846
noInterrupts();
4947
v_tgt = v_tgt_orig * factor;
5048
dv = v_tgt > v_cur ? dv_cur : -dv_cur;
@@ -87,4 +85,3 @@ void LinRotAccelerator::eStop()
8785
v_tgt = 0.0f;
8886
interrupts();
8987
}
90-

src/accelerators/LinStepAccelerator.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@ class LinStepAccelerator
3030
int32_t LinStepAccelerator::prepareMovement(int32_t currentPos, int32_t targetPos, uint32_t targetSpeed, uint32_t a)
3131
{
3232
s_0 = currentPos;
33-
delta_tgt = std::abs(targetPos - currentPos);
33+
delta_tgt = abs(targetPos - currentPos);
3434
v_tgt = targetSpeed;
3535
two_a = 2 * a;
3636
v_min2 = a;
@@ -44,7 +44,7 @@ int32_t LinStepAccelerator::prepareMovement(int32_t currentPos, int32_t targetPo
4444

4545
int32_t LinStepAccelerator::updateSpeed(int32_t curPos)
4646
{
47-
uint32_t stepsDone = std::abs(s_0 - curPos);
47+
uint32_t stepsDone = abs(s_0 - curPos);
4848

4949
// acceleration phase -------------------------------------
5050
if (stepsDone < accLength)
@@ -64,7 +64,7 @@ int32_t LinStepAccelerator::updateSpeed(int32_t curPos)
6464

6565
uint32_t LinStepAccelerator::initiateStopping(int32_t curPos)
6666
{
67-
uint32_t stepsDone = std::abs(s_0 - curPos);
67+
uint32_t stepsDone = abs(s_0 - curPos);
6868

6969
if (stepsDone < accLength) // still accelerating
7070
{

src/timer/teensy3/config.h

+21-21
Original file line numberDiff line numberDiff line change
@@ -7,10 +7,10 @@ namespace TeensyStepFTM
77
{
88

99

10-
//==========================================================================
11-
// Available timer modules for the Teensy XX boards. Please note that those
12-
// timers are also used by the core libraries for PWM and AnalogWrite.
13-
// Therefore, choose a timer which isn't attached to the pins you need for
10+
//==========================================================================
11+
// Available timer modules for the Teensy XX boards. Please note that those
12+
// timers are also used by the core libraries for PWM and AnalogWrite.
13+
// Therefore, choose a timer which isn't attached to the pins you need for
1414
// PWM or AnalogWrite. (TEENSY LC not yet supported)
1515
//
1616
// D: Default, X: available
@@ -32,14 +32,14 @@ namespace TeensyStepFTM
3232

3333

3434
//==========================================================================
35-
// Nothing to be changed below here
35+
// Nothing to be changed below here
3636
//==========================================================================
3737

3838

3939

4040
#if USE_TIMER == TIMER_DEFAULT
4141
#undef USE_TIMER
42-
#if defined __MKL26Z64__
42+
#if defined __MKL26Z64__
4343
#define USE_TIMER TIMER_TPM0
4444
#else
4545
#define USE_TIMER TIMER_FTM0
@@ -57,15 +57,15 @@ namespace TeensyStepFTM
5757
T_LC, T_30, T31_2, T_35, T_36
5858
};
5959

60-
#if defined __MKL26Z64__
60+
#if defined __MKL26Z64__
6161
constexpr _boards board = _boards::T_LC;
62-
#elif defined __MK20DX128__
62+
#elif defined __MK20DX128__
6363
constexpr _boards board = _boards::T_30;
64-
#elif defined __MK20DX256__
64+
#elif defined __MK20DX256__
6565
constexpr _boards board = _boards::T31_2;
66-
#elif defined __MK64FX512__
66+
#elif defined __MK64FX512__
6767
constexpr _boards board = _boards::T_35;
68-
#elif defined __MK66FX1M0__
68+
#elif defined __MK66FX1M0__
6969
constexpr _boards board = _boards::T_36;
7070
#endif
7171

@@ -138,33 +138,33 @@ namespace TeensyStepFTM
138138
8, // FTM3
139139
6, // TPM0
140140
2, // TPM1
141-
2, // TPM2
141+
2, // TPM2
142142
};
143143

144144
constexpr uintptr_t timerAddr = TimerBaseAddr[(int)board][selTimer];
145-
constexpr volatile FTM_t* timer = __builtin_constant_p((FTM_t*)timerAddr) ? (FTM_t*)timerAddr : (FTM_t*)timerAddr; // base address for register block of selected timer
146-
constexpr unsigned irq = IRQ_Number[(int)board][selTimer]; // IRQ number of selected timer
147-
constexpr unsigned maxChannel = _nrOfChannels[selTimer]; // Number of channels for selected timer
145+
volatile FTM_t *const timer = (FTM_t *)timerAddr; // base address for register block of selected timer
146+
constexpr unsigned irq = IRQ_Number[(int)board][selTimer]; // IRQ number of selected timer
147+
constexpr unsigned maxChannel = _nrOfChannels[selTimer]; // Number of channels for selected timer
148148

149-
static_assert(timer != nullptr && irq != 0, "Board does not support choosen timer"); //Generate compiler error in case the board does not support the selected timer
149+
static_assert(timerAddr != 0 && irq != 0, "Board does not support choosen timer"); //Generate compiler error in case the board does not support the selected timer
150150

151151
//-----------------------------------------------------------------------------------
152-
//Frequency dependent settings
152+
//Frequency dependent settings
153153

154154
constexpr unsigned _timer_frequency = isFTM ? F_BUS : 16000000; // FTM timers are clocked with F_BUS, the TPM timers are clocked with OSCERCLK (16MHz for all teensies)
155155

156156
// Choose prescaler such that one timer cycle corresponds to about 1µs
157-
constexpr unsigned prescale =
157+
constexpr unsigned prescale =
158158
_timer_frequency > 120000000 ? 0b111 :
159159
_timer_frequency > 60000000 ? 0b110 :
160-
_timer_frequency > 30000000 ? 0b101 :
160+
_timer_frequency > 30000000 ? 0b101 :
161161
_timer_frequency > 15000000 ? 0b100 :
162162
_timer_frequency > 8000000 ? 0b011 :
163163
_timer_frequency > 4000000 ? 0b010 :
164164
_timer_frequency > 2000000 ? 0b001 : 0b000;
165165

166-
// Calculates required reload value to get a delay of mu microseconds.
167-
// this will be completely evaluated by the compiler as long as mu is known at compile time
166+
// Calculates required reload value to get a delay of mu microseconds.
167+
// this will be completely evaluated by the compiler as long as mu is known at compile time
168168
constexpr int microsToReload(const float mu)
169169
{
170170
return mu * 1E-6 * _timer_frequency / (1 << prescale) + 0.5;

0 commit comments

Comments
 (0)