3

I, at the moment am trying to come up with a simple way where I can program an Arduino to provide a step signal with a given frequency, at a specific time.

The frequency has to be ramped up, and within a time duration of 10 seconds shall the frequency go from 0 Hz to 48000 Hz.

How do I ensure both the specific time of when the frequency occurs, and the specific frequency of the step signal?

Signal has to be used to driver a stepper motor.

Edit: Code current:

So i currently wrote this piece of code:

int timestep = 1;
while(1)
{
  unsigned long startTime = millis()
  while(startTime != 500)
  {  
    digitalWrite(step_pin,LOW);
    delayMicroseconds(208/timestep);
    digitalWrite(step_pin,HIGH);
    delayMicroseconds(208/timestep);
  }  

  timestep++;
}

For each 0.5s should the frequency be doubled.. would this work?

Edit 2.0:

I made an new implementation using @EdgarBonet 's answer, and with the help of Timer1 library that arduino provide (I guess?).

.h file

#ifndef stepper_motor_h
#define stepper_motor_h

#include "Arduino.h"
#include <TimerOne.h>

#define step_pin  13
#define dir_pin   12
#define en_pin    11
#define max_step  200

 class stepper_motor
{
  public:
    stepper_motor();
    void step_pwm();
    static void callback();
    TimerOne timer1;
  private:
    //uint32_t period;
    bool alive_bool;    
    //int step_count;
    bool position_bool;
};


#endif

.cpp file

#include "stepper_motor.h"

int step_count = 0;
uint32_t period = 40825UL << 16; // 20412,5 us fixed point arithmetic time = 0

stepper_motor::stepper_motor()
{
  //pinMode(BUILTIN_LED,OUTPUT);
  pinMode(step_pin, OUTPUT);
  pinMode(dir_pin, OUTPUT);
  pinMode(en_pin, OUTPUT);
  alive_bool = true;
  position_bool = false;
  step_count = 0;

}

static void stepper_motor::callback()
{
  if (step_count < 240)
  {
    uint32_t new_period = sqrt(2 * step_count / 4.8);
    period -= new_period; 
    step_count++;
  }
  else
  {
    return;
  }
}


void stepper_motor::step_pwm()
{

  digitalWrite(en_pin, HIGH);

  delay(0.005);

  digitalWrite(dir_pin, HIGH);
  //LOW  - Move towards the sensor
  //HIGH -  Move away from the sensor

  delay(0.005);

  timer1.initialize(period);
  timer1.attachInterrupt(callback);
  timer1.pwm(step_pin, 512);


}
4
  • By “step signal” you mean a square signal? I would use Timer 1 for that, but this is more AVR programming than Arduino programming. Do you need the ramp to be linear? Commented Sep 27, 2016 at 20:52
  • Sounds like you need to model your ramping function's acceleration such that you can calculate exactly how long in advance you need to start it in order to hit the target rate at exactly the target time. Commented Sep 27, 2016 at 21:38
  • yes to the above questions.. Commented Sep 28, 2016 at 2:54
  • At 48 kHz, you have to toggle the output every 10.4 µs. If you try to do this in software, you will get an awful lot of jitter, unless you use hand-tuned assembly with interrupts disabled. On this time scale, a hardware timer is the simplest way to get consistent timings. Commented Sep 28, 2016 at 15:46

3 Answers 3

3

Generating a linear frequency ramp with accurate timings is not an easy task. I am providing here only a partial answer, where I first go through the math of the problem, then give some ideas for the implementation.

The math

We are dealing with a frequency-modulated signal, with the frequency ramping linearly from f = 0 at t = 0 up to a maximum f = fM at t = tM. Specifically, we have fM = 48 kHz and tM = 10 s. Then, the instantaneous frequency is

f(t) = a t

where a = fM/tM = 4.8 kHz/s is the “acceleration” of the pulsed signal.

Let's define the “integrated frequency” as

n(t) = ∫ f(t) dt = a t²/2

This quantity can be interpreted as the number of cycles completed at time t, except that it is a continuous variable. The first cycle starts when n = 0 and ends when n = 1, the next cycle starts when n = 1 and ends when n = 2, and so on. The output signal would be high when the fractional part of n is between 0.25 and 0.75 (or maybe between 0 and 0.5, depending on your choice of initial phase).

From here, we can calculate at what time each cycle should start:

t(n) = √(2 n/a)

and, by successive differences, the length of each cycle:

n       0     1       2       3      ... 239,998    239,999    240,000
t       0     20,412  28,868  35,355 ... 9,999,958  9,999,979  10,000,000
length   20,412   8,455   6,488      ...        20.833     20.833
diff          -11,957 -1,967  -1,018 ...            -0.000043
approx        +81,650 -1,408  -913   ...            -0.000043

In the table above, all times are in microseconds. The lines are:

  • t: time
  • length: length of one cycle
  • diff: difference between lengths of successive cycles
  • approx: approximated formula for that difference

The columns are staggered because each cycles spans the duration between two successive values of t, and duration differences are computed between successive cycles. The approximated formula is based on the Taylor expansion:

T(n+1) − T(n) ≈ dT/dn + 1/2 d²T/dn² = −aT³(1 − 3/2 aT²)

where T = 1/f, the instantaneous period, approximates the length of one cycle. The approximation is not good for the very first cycles, but it converges pretty fast to the correct value.

Implementation

I did not write an implementation, so I am giving here only some ideas on how to do it.

I would use Timer 1 of the Arduino Uno, in one of the modes that allows frequency-modulation, i.e. a PWM mode where the counter TOP is set by a register (mode 8, 9, 10, 11, 14 or 15). I would set the prescaler to 8 in order to allow for the maximum required period length. The period resolution would then be:

  • 8 CPU cycles = 0.5 µs in modes 14 or 15 (fast PWM)
  • 16 CPU cyels = 1 µs in the other modes

It could be noted that single-cycle resolution is possible with the prescaler set to 1, but the first 5 cycles are too long for this setting. Maybe the prescaler could be changed after the fifth cycle, but it would be tricky to do so without any glitch.

The timer overflow interrupt would fire at the end of each cycle, and it's ISR (namely TIMER1_OVF_vect) would be responsible for updating the timer period in order to make the next cycle shorter than the one just elapsed. It would do something like

period -= delta(period);

The period should be computed with 32-bit arithmetic, because the changes get tiny by the end of the ramp. Only the 16 most significant bits of the computed period would actually be written to the timer register. The delta() function should be inlined and fast. I may try the approximation from the previous section implemented in fixed-point. Or maybe just a table lookup using only the most significant bits of the period as an index, with the table in PROGMEM.

For details on how to actually program the timer, see the datasheet of the ATmega328P, section 16.


Update: The following algorithm seems to work well. At least in simulation, I did not put it inside an ISR. It assumes fast PWM, i.e. a 0.5 µs timer resolution. It remembers the current value of delta and divides it by 2 each time the period falls below some threshold. The computed f(t) is almost as smooth as you can expect given the limited resolution of the timer.

uint32_t period = 40825UL << 16;  // 1st cycle is 20412.5 us
void update_period()  // should be in ISR(TIMER1_OVF_vect)
{
    static const uint16_t thresholds[] = {
            17633, 13309, 10229, 7954, 6230, 4905, 3873, 3063,
            2426, 1923, 1525, 1211, 960, 762, 605, 480, 381,
            302, 240, 190, 151, 120, 95, 76, 60, 48};
    static uint16_t threshold = 29000;
    static uint8_t index = 0;
    static uint32_t delta = 6UL << 27;

    uint16_t period_h = period >> 16;
    if (period_h <= 42) return;  // final frequency achieved
    if (period_h < threshold) {
        threshold = thresholds[index++];
        delta >>= 1;
    }
    period -= delta;
    // set the timer period register to (period >> 16) - 1.
}
13
  • this might be me who is being stupid.. I have some question regarding the math you introduce. f(t) => the linear increase of the frequency i am interested in. -> Makes sense.. N(t) => the integrated frequency => provides the number of cycles completed at time t. number of cycles pr. unit time => the frequency. What do i gain from n(t) which i do not gain from f(t)? Commented Sep 29, 2016 at 7:44
  • @CarltonBanks: n(t) is a number of cycles, it's not a number of cycles per unit time. It's most useful for computing the length of the very first cycle (≈ 20.4 ms). From the frequency alone, it's hard to tell: what should be the initial period given that the initial frequency is zero? Commented Sep 29, 2016 at 7:58
  • So you basically use n(t) to know how many cycles should be completed at the given time, such that you can adjust the period to allign with n(t)? Commented Sep 29, 2016 at 8:40
  • you actually using n(t) to kickstart the system, as you say, that having frequency = 0 would not create a computable period. Commented Sep 29, 2016 at 8:41
  • how do you get the t(n) expression ? Commented Sep 29, 2016 at 8:42
3

As mentioned in comments and other answers, using timer 1 for hardware-timed bit toggling is likely to produce better results than code using delays based on calls like delayMicroseconds(), primarily because of overhead causing poor resolution or jitter.

Using timer 1 in a PWM mode offers an advantage: loading of the OCR1A register is double buffered in PWM modes. This makes it possible to smoothly transition from one frequency to another without glitches due to setup delays. The code shown below (program freqSweep.ino) illustrates one way of steadily ramping the period of a waveform. The initial count, delta count, and number of steps parameters ic, dc, ns also are double buffered, with the first set loaded via rampInit (), and new sets loaded opportunely from time to time via rampNext ().

In operation, the ramper causes timer 1 to produce a waveform with half cycles of lengths ic, ic+dc, ic+2dc, ... ic+(ns-1)dc. That is, it generates ns steps of varying lengths, using timer 1 interrupts to trigger its execution in the background. While the ISR produces a ramp of cycles, the user's loop() code can be computing parameters for the next ramp. Note, if dc>0, periods grow larger so the frequency ramp descends. If dc<0, periods grow smaller so the frequency ramp ascends. If dc==0, the ramp is flat. Note, ic and dc are 32-bit fixed-point numbers, with 16 binary places. Thus, while hardware only generates time intervals with integral numbers of cycles, the ramper software works with fractional values, so dc can have values like 0.5, 3.375, .076171875 (39/512) etc.

By generating a seamless series of small ramps, one can accurately approximate larger patterns of frequency ramps. For example, to generate a frequency-linear ramp from say 100 Hz up to 48 KHz in 10 seconds, one might divide that time into 100 parts. If f(t) denotes the frequency desired at time t, one would then (for each 0.1 second time step) compute half-periods p and q corresponding to frequencies f(t) and f(t+0.1). About n = 0.1*f(t+0.05) cycles are available in 0.1 seconds for frequencies between f(t) and f(t+0.1), or about ns = 2*n half-cycles. Choose dc = (q-p)/ns [using 32:16 fixed point arithmetic, and noting that dc can be negative] to smoothly ramp from frequency f(t) to f(t+0.1) in ns steps that take about 0.1 seconds total. 0.1 seconds, or 100 ms, is enough time to calculate and load a new set of parameters. See program comments (under the heading General form of use of ramper) re computing parameters.

Here is the example program:

// Sweep a frequency, on dig. pin 7, PD7 - jw 27 Sep 2016
#include <Streaming.h>

enum { outpin=7, mOutpin=1<<7 }; // Arduino dig. pin# & its bit mask
void setup() {
  pinMode(outpin, OUTPUT);
}

long RAMdcl, RAMdcn;    // dc is signed to allow ramps up or down
unsigned long RAMicl, RAMicn; 
unsigned int RAMnsl, RAMnsn;
volatile unsigned int RAMrampsDone; // Number of ramps done so far
volatile byte RAMsendPars;  // Flag is 1 when ok to send params

void rampInit(unsigned long ic0, unsigned long dc0, unsigned long ns0, byte clockSource) {
  /* clockSource should be a 3-bit number, from 0 to 5:
   ..Bits.. ....Effect....   [See Table 16-5, p. 134 in specs]
    0 0 0   No clock source (Timer/Counter stopped).
    0 0 1   IOclock / 1    (No prescaling)
    0 1 0   IOclock / 8    (From prescaler)
    0 1 1   IOclock / 64   (From prescaler)
    1 0 0   IOclock / 256  (From prescaler)
    1 0 1   IOclock / 1024 (From prescaler)
  */
  TIMSK1 = 0;           // Turn off timer 1 interrupts
  // ic and dc (initial count and delta count) values
  // are 32:16 fixed point values; ie with 16 binary places.
  RAMicl = RAMicn = ic0;
  RAMdcl = RAMdcn = dc0;    // Set initial param values
  RAMnsl = RAMnsn = ns0;
  RAMrampsDone = 0;     // No ramps done yet
  RAMsendPars = 1;      // Next param set can load

    // Set timer 1 to Fast Pwm mode with OC1A (dig pin 9) toggling
  TCNT1 = 0;           // Zero the counter
  TCCR1A = 1<<WGM11 | 1<<WGM10; // for Fast Pwm with TOP from OCR1A
  OCR1A = (uint16_t)(RAMicl >> 16); // Initial TOP = integer part of icl
  TCCR1B = 1<<WGM13 | 1<<WGM12 | // for Fast Pwm with TOP from OCR1A
           clockSource;    // Start timer 1 with selected prescale
  TIMSK1 = 1<<TOIE1;       // Enable timer 1 overflow interrupt at TOP
}

// timer 1 overflow interrupt handler
ISR(TIMER1_OVF_vect) {
  OCR1A = (uint16_t)(RAMicl >> 16); // Update TOP with integer part of ic
  PIND = mOutpin;         // Toggle the output pin, eg dig pin 7, PD7
  // (Output bits toggle when a 1 is written to their input port bit)

  RAMicl += (unsigned long)RAMdcl;  // dc is signed but we need bare bits 
  --RAMnsl;
  if (!RAMnsl) {        // Go on to next section?
    RAMicl = RAMicn;
    RAMdcl = RAMdcn;        // Set next param values
    RAMnsl = RAMnsn;
    ++RAMrampsDone;     // We are in the last half cycle of section
    RAMsendPars = 1;        // Ready for next param set
  }
}

// rampNext() busy-waits until it can load new param values
void rampNext (unsigned long ic, unsigned long dc, unsigned int ns) {
  while (!RAMsendPars) {}
  RAMsendPars = 0;
  RAMicn = ic;
  RAMdcn = dc;      // Set next param values
  RAMnsn = ns;
}

// rampStop() stops the ramp-processor, right now
void  rampStop() {
  TIMSK1 = 0;           // Turn off timer 1 interrupts
  RAMrampsDone = RAMsendPars = 0;
  digitalWrite(outpin, LOW);    // Turn off output bit
}

/*
  // General form of use of ramper:
  ...
  rampInit(icj, dcj, nsj, scaleBy1);  // Send first param set
  for (byte j=0; j<rampSections; ++j) {
    // Compute next param set ...
    icj = ...
    dcj = ...
    nsj = ...
    // Do other stuff here
    // ...
    // rampNext will busy-wait while sendPars is clear
    rampNext (icj, dcj, nsj);
  }
  // Busy-wait while last ramp finishes
  while (RAMrampsDone <= rampSections) {}
  rampStop();       // Stop the ramp-processor
*/

// Example: Play a sound with 5 ramp parts in loop(), with brief pauses
void loop() {
  enum { scaleBy1=1};
  unsigned long icj, dcj;       // My ramp param calc vars
  unsigned int nsj=1000;        // # of steps per ramp
  icj = ((unsigned long)1600)<<16;  // ic = initial count
  dcj = ((unsigned long)1)<<16;     // dc = step size
  nsj = 5000;
  rampInit (icj*3, dcj/2, nsj, scaleBy1);
  rampNext (icj, dcj, nsj/3);
  rampNext (icj*2, -dcj, nsj/2);
  rampNext (icj*2, -dcj, nsj/2);
  rampNext (icj, dcj, nsj/3);
  while (RAMrampsDone < 5) {};
  rampStop();           // Stop the ramp-processor
  delay(2500);          // silence-separator
}
2
  • This is great! A few suggestions: 1) You can have the timer generate the output on OC1A = PB1 = digital 9 by setting COM1A0 in TCCR1A. This is cleaner than doing it in software, as your ISR will sometimes be delayed by, e.g. TIMER0_OVF. 2) Putting (ic, dc, ns) in a struct makes the source better structured and the compiled code more compact: it saves 104 bytes of flash. 3) The dc0/dc arguments to rampInit() and rampNext() should be signed, and ns0 of rampInit() should not be long. 4) The casts to uint16_t on lines 37 and 45, and to unsigned long on line 49 serve no purpose. Commented Sep 29, 2016 at 9:29
  • @EdgarBonet, thanks for the comments! 1) Yes, I wanted to do that, to avoid jitter, but probably had COM1A1 set by mistake instead of COM1A0. 2) I'll try that -- it will be (ic, dc, ns, cs) where cs is clock source -- I think I've figured out how to change cs without glitching part of a cycle. 3) Agreed, noticed those inconsistencies a few hours after posting. 4) Ok. Anyhow, I'll revise the posted code in a couple of days - work is in the way at present Commented Sep 30, 2016 at 1:51
0

There are three points:

  1. Try to work in the terms of pulse duration. 48 000 Hz will give say 167 ticks for 8 MHz clock (83 ticks for HIGH level on active pin and 83 - LOW). Division on fly is very time consuming, so better to use period instead of frequency. 0 - switch the timer off. 1 Hz - 8 000 000 ticks (4000000 for High and 4000000 for LOW).

  2. As I understand the stepper motor will have to drive some load, so acceleration needed depends not only on the parameters of motor itself but on the total mechanical system. So, to calculate needed data from the scratch will be rather difficult and inaccurate. Better try to calibrate the system. Tat will take a piece of job but will be more accurate.

  3. You do not need to make smooth decrease of period but you can use several predefined steps. This will give you two arrays t[i] for period to be set in timer and d[i] - number of steps, done with this period. The total time for the given period will be d[i]*t[i]. The total time of acceleration then will be the simple sum of time slices in the sequence i from 0 to max. So you can get it rather accurately.

It will take at least two timers - one for the period setting, other for counting periods in a time slice. After one time slice is finished you just increment array index and load new data in timers. Calibration will take to define best real data for array t[] and d[].

If you will hold in t[] half-periods, then you need to double values in d[], or taking values from t[] you can divide them by 2 (it's a simple shift so it takes little time) for one half-period is HIGH and next is LOW. The decision is up to you.

1
  • I updated the post with some code.. would this work.. Commented Sep 28, 2016 at 9:13

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.