Arduino zero generate PPS with hardware timer

Hi, I am trying to use hardware timer to generate PPS every 1s, with 100ms pulse High and 900ms pulse low. The pulse generate at beginning of every second.

I first check Martin's suggestion for interrupt each 1s. I did a little change, my code is below. Basicly, just add ROS to time message and add pulse generation at TC4_Handler.

#define USE_USBCON

#include <ros.h>
#include <std_msgs/Header.h>
#define PPS_TRIGGER_PIN 16 // pps not stable

ros::NodeHandle nh;
std_msgs::Header header;
ros::Publisher timer("timer", &header);
volatile boolean isRead = false;

// Set timer TC4 to call the TC4_Handler every second
void setup() {
  nh.initNode();
  nh.advertise(timer);

  pinMode(PPS_TRIGGER_PIN, OUTPUT);
  digitalWrite(PPS_TRIGGER_PIN, LOW);

  // Set up the generic clock (GCLK4) used to clock timers
  REG_GCLK_GENDIV = GCLK_GENDIV_DIV(1) |          // Divide the 48MHz clock source by divisor 1: 48MHz/1=48MHz
                    GCLK_GENDIV_ID(4);            // Select Generic Clock (GCLK) 4
  while (GCLK->STATUS.bit.SYNCBUSY);              // Wait for synchronization

  REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC |           // Set the duty cycle to 50/50 HIGH/LOW
                     GCLK_GENCTRL_GENEN |         // Enable GCLK4
                     GCLK_GENCTRL_SRC_DFLL48M |   // Set the 48MHz clock source
                     GCLK_GENCTRL_ID(4);          // Select GCLK4
  while (GCLK->STATUS.bit.SYNCBUSY);              // Wait for synchronization

  // Feed GCLK4 to TC4 and TC5
  REG_GCLK_CLKCTRL = GCLK_CLKCTRL_CLKEN |         // Enable GCLK4 to TC4 and TC5
                     GCLK_CLKCTRL_GEN_GCLK4 |     // Select GCLK4
                     GCLK_CLKCTRL_ID_TC4_TC5;     // Feed the GCLK4 to TC4 and TC5
  while (GCLK->STATUS.bit.SYNCBUSY);              // Wait for synchronization

  REG_TC4_COUNT16_CC0 = 0xB71A;                   // Set the TC4 CC0 register as the TOP value in match frequency mode
  while (TC4->COUNT16.STATUS.bit.SYNCBUSY);       // Wait for synchronization

  //NVIC_DisableIRQ(TC4_IRQn);
  //NVIC_ClearPendingIRQ(TC4_IRQn);
  NVIC_SetPriority(TC4_IRQn, 0);    // Set the Nested Vector Interrupt Controller (NVIC) priority for TC4 to 0 (highest)
  NVIC_EnableIRQ(TC4_IRQn);         // Connect TC4 to Nested Vector Interrupt Controller (NVIC)

  REG_TC4_INTFLAG |= TC_INTFLAG_OVF;              // Clear the interrupt flags
  REG_TC4_INTENSET = TC_INTENSET_OVF;             // Enable TC4 interrupts
  // REG_TC4_INTENCLR = TC_INTENCLR_OVF;          // Disable TC4 interrupts

  REG_TC4_CTRLA |= TC_CTRLA_PRESCALER_DIV1024 |   // Set prescaler to 1024, 48MHz/1024 = 46.875kHz
                   TC_CTRLA_WAVEGEN_MFRQ |        // Put the timer TC4 into match frequency (MFRQ) mode 
                   TC_CTRLA_ENABLE;               // Enable TC4
  while (TC4->COUNT16.STATUS.bit.SYNCBUSY);       // Wait for synchronization
}

void loop() {
  while(!isRead);                                 // Block until the trigger() function returns
  isRead = false;                                 // Reset the count read flag
  timer.publish( &header );

  nh.spinOnce();
}

void TC4_Handler()                              // Interrupt Service Routine (ISR) for timer TC4
{     
  // Check for overflow (OVF) interrupt
  if (TC4->COUNT16.INTFLAG.bit.OVF && TC4->COUNT16.INTENSET.bit.OVF)             
  {
    // Put your timer overflow (OVF) code here:     
    // ...
    header.stamp = nh.now();
    isRead = true;

    digitalWrite(PPS_TRIGGER_PIN, HIGH);
    delayMicroseconds(100000);
    digitalWrite(PPS_TRIGGER_PIN, LOW);

    REG_TC4_INTFLAG = TC_INTFLAG_OVF;         // Clear the OVF interrupt flag
  }
}

The output time are shown below:

secs: 1617982338
nsecs: 583847082

secs: 1617982339
nsecs: 484847082

secs: 1617982340
nsecs: 385847082

secs: 1617982341
nsecs: 583608999

secs: 1617982342
nsecs: 484608999

secs: 1617982343
nsecs: 385608999

So the timer is seems like interrupt as 900ms, 900ms, 1200ms, 900ms, 900ms... It's definitely related to my generated pulse which is about 100ms. When I remove those pulse generation line, timer works fine.

Any suggestions will be grateful, thanks.

@crazymumu To generate jitter free pulses using a TC timer, it's possible to configure it in match PWM mode (MPWM) and route the signal to an output pin. This allows the timer generate an output that is independent of any code delays.

The following code generates a 100ms pulse every second on digital pin D12 (PA19 on the Arduino Zero):

// Set timer TC3 generate a 100ms pulse every second on D12 (PA19)
void setup() 
{
  GCLK->CLKCTRL.reg = GCLK_CLKCTRL_CLKEN |                 // Connect GCLK0 at 48MHz as a clock source for TCC2 and TC3
                      GCLK_CLKCTRL_GEN_GCLK0 |             
                      GCLK_CLKCTRL_ID_TCC2_TC3;            

  // Enable D12's peripheral multiplexer
  PORT->Group[g_APinDescription[12].ulPort].PINCFG[g_APinDescription[12].ulPin].bit.PMUXEN = 1;
  // Set D12 multiplexer switch to position E
  PORT->Group[g_APinDescription[12].ulPort].PMUX[g_APinDescription[12].ulPin >> 1].reg |= PORT_PMUX_PMUXO_E;
  
  TC3->COUNT16.CC[0].reg = 46874;                          // Set the TC3 CC0 register to generate a 1 second period
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization

  TC3->COUNT16.CC[1].reg = 4688;                           // Set the TC3 CC1 register to generate a duty cycle of 10% (100ms)
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization

  //NVIC_SetPriority(TC3_IRQn, 0);    // Set the Nested Vector Interrupt Controller (NVIC) priority for TC3 to 0 (highest)
  //NVIC_EnableIRQ(TC3_IRQn);         // Connect TC3 to Nested Vector Interrupt Controller (NVIC)

  //TC3->COUNT16.INTENSET.reg = TC_INTENSET_OVF;             // Enable TC3 overflow (OVF) interrupts
 
  TC3->COUNT16.CTRLA.reg = TC_CTRLA_PRESCSYNC_PRESC |      // Reset timer on the next prescaler clock
                           TC_CTRLA_PRESCALER_DIV1024 |    // Set prescaler to 1024, 48MHz/1024 = 46875kHz
                           TC_CTRLA_WAVEGEN_MPWM |         // Put the timer TC3 into match pulse width modulation (MPWM) mode 
                           TC_CTRLA_MODE_COUNT16;          // Set the timer to 16-bit mode      
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization

  TC3->COUNT16.CTRLA.bit.ENABLE = 1;                       // Enable the TC3 timer
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization
}

void loop() {}

void TC3_Handler()                                         // Interrupt Service Routine (ISR) for timer TC3
{      
  if (TC3->COUNT16.INTFLAG.bit.OVF && TC3->COUNT16.INTENSET.bit.OVF)       // Optionally check for overflow (OVF) interrupt      
  {   
     TC3->COUNT16.INTFLAG.bit.OVF = 1;                     // Clear the overflow (OVF) interrupt flag
     // Add optional ISR code here...
  }
}

Note that I've included the optional TC3 interrupt service routine as well, but have commented out the lines of code that enable it. I used timer TC3 in preference to TC4, simply because it has outputs located on more convenient pins.

Hi @MartinL , much appreciated for your reply.
For the PPS mechanism to work, I need to know when is the PPS is generated. So I add some line to measure time in the TC3_Handler and enabled the TC3, if that's the way to do it. The time output is correct to me.
Also, I have some questions summarized below, hope you can help me when you have time:

  1. For the PPS mechanism to work, I need to send PPS at the beginning of every second. Do you have any idea how to do that?
  2. For the PPS time output, it has 1 millisecond drift about every 2s, I guess that's the normal performance. Can we do something to correct this drift this? Because I using PPS to do sensor time synchronization in no GPS environment.
  3. In our current setup, I am using D13 for PPS generation, If I use TCC2 for D13, it should be still good, right?

Thanks for your time.

@crazymumu

My apologies, the reason for the drift is because I entered the wrong values into the CC0 and CC1 registers. I've corrected the code above. It should be:

  TC3->COUNT16.CC[0].reg = 46874;                          // Set the TC3 CC0 register to generate a 1 second period
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization

  TC3->COUNT16.CC[1].reg = 4688;                           // Set the TC3 CC1 register to generate a duty cycle of 10% (100ms)
  while (TC3->COUNT16.STATUS.bit.SYNCBUSY);                // Wait for synchronization

The TCC2 timer configuration is a little bit different, but along the same lines:

// Set timer TCC2 generate a 100ms pulse every second on D13 (PA17)
void setup() 
{
  GCLK->CLKCTRL.reg = GCLK_CLKCTRL_CLKEN |       // Connect GCLK0 at 48MHz as a clock source for TCC2 and TC3
                      GCLK_CLKCTRL_GEN_GCLK0 |             
                      GCLK_CLKCTRL_ID_TCC2_TC3;            

  // Enable D13's peripheral multiplexer
  PORT->Group[g_APinDescription[13].ulPort].PINCFG[g_APinDescription[13].ulPin].bit.PMUXEN = 1;
  // Set D13 multiplexer switch to position
  PORT->Group[g_APinDescription[13].ulPort].PMUX[g_APinDescription[13].ulPin >> 1].reg |= PORT_PMUX_PMUXO_E;
  
  TCC2->WAVE.reg = TCC_WAVE_WAVEGEN_NPWM;        // Configure the TCC2 timer for normal PWM mode
  while (TCC2->SYNCBUSY.bit.WAVE);               // Wait for synchronization
  
  TCC2->PER.reg = 46874;                         // Set the TCC2 PER register to generate a 1 second period
  while (TCC2->SYNCBUSY.bit.PER);                // Wait for synchronization

  TCC2->CC[1].reg = 4688;                        // Set the TCC2 CC1 register to generate a duty cycle of 10% (100ms)
  while (TCC2->SYNCBUSY.bit.CC1);                // Wait for synchronization

  //NVIC_SetPriority(TCC2_IRQn, 0);    // Set the Nested Vector Interrupt Controller (NVIC) priority for TCC2 to 0 (highest)
  //NVIC_EnableIRQ(TCC2_IRQn);         // Connect TCC2 to Nested Vector Interrupt Controller (NVIC)

  //TCC2->INTENSET.reg = TCC_INTENSET_OVF;       // Enable TCC2 overflow (OVF) interrupts
 
  TCC2->CTRLA.reg = TCC_CTRLA_PRESCSYNC_PRESC |   // Reset timer on the next prescaler clock
                    TCC_CTRLA_PRESCALER_DIV1024;  // Set prescaler to 1024, 48MHz/1024 = 46875kHz                       
  
  TCC2->CTRLA.bit.ENABLE = 1;                    // Enable the TCC2 timer
  while (TCC2->SYNCBUSY.bit.ENABLE);             // Wait for synchronization
}

void loop() {}

void TCC2_Handler()                                         // Interrupt Service Routine (ISR) for timer TCC2
{      
  if (TCC2->INTFLAG.bit.OVF && TCC2->INTENSET.bit.OVF)      // Optionally check for overflow (OVF) interrupt      
  {   
    TCC2->INTFLAG.bit.OVF = 1;                              // Clear the overflow (OVF) interrupt flag
    // Add optional ISR code here...
  }
}

Hi @MartinL , real appreciated for your reply. After your modification, the time drift seems still there but do improved, it's drift about each 5~6 second. I am thinking maybe this is just normal performance. Here is the time output:

---
  secs: 1619111807
  nsecs: 657234430
---
  secs: 1619111808
  nsecs: 657234430
---
  secs: 1619111809
  nsecs: 657234430
---
  secs: 1619111810
  nsecs: 656072616
---
  secs: 1619111811
  nsecs: 656072616
---
  secs: 1619111812
  nsecs: 656072616
---
  secs: 1619111813
  nsecs: 655569314
---
  secs: 1619111814
  nsecs: 655569314
---
  secs: 1619111815
  nsecs: 655569314
---
  secs: 1619111816
  nsecs: 655259370
---
  secs: 1619111817
  nsecs: 655259370
---
  secs: 1619111818
  nsecs: 655259370
---
  secs: 1619111819
  nsecs: 654378414
---
  secs: 1619111820
  nsecs: 654378414
---
  secs: 1619111821
  nsecs: 654378414
---
  secs: 1619111822
  nsecs: 654622554
---
  secs: 1619111823
  nsecs: 654622554
---
  secs: 1619111824
  nsecs: 654622554
---
  secs: 1619111825
  nsecs: 653389453
---
  secs: 1619111826
  nsecs: 653389453
---
  secs: 1619111827
  nsecs: 653389453
---
  secs: 1619111828
  nsecs: 653118371
---
  secs: 1619111829
  nsecs: 653118371
---
  secs: 1619111830
  nsecs: 653118371
---
  secs: 1619111831
  nsecs: 653573989
---
  secs: 1619111832
  nsecs: 653573989
---
  secs: 1619111833
  nsecs: 653573989
---
  secs: 1619111834
  nsecs: 652498722
---
  secs: 1619111835
  nsecs: 652498722
---
  secs: 1619111836
  nsecs: 652498722
---
  secs: 1619111837
  nsecs: 651913166
---
  secs: 1619111838
  nsecs: 651913166
---
  secs: 1619111839
  nsecs: 651913166
---
  secs: 1619111840
  nsecs: 652557134
---
  secs: 1619111841
  nsecs: 652557134
---
  secs: 1619111842
  nsecs: 652557134
---
  secs: 1619111843
  nsecs: 651592254
---
  secs: 1619111844
  nsecs: 651592254
---
  secs: 1619111845
  nsecs: 651592254
---
  secs: 1619111846
  nsecs: 650991916
---
  secs: 1619111847
  nsecs: 650991916
---
  secs: 1619111848
  nsecs: 650991916
---
  secs: 1619111849
  nsecs: 650460958
---
  secs: 1619111850
  nsecs: 650460958

May I have another question? The PPS here is send after 0.655 s after beginning of each second. Is that possible to re-schedule to send PPS at 1.000, 2.000, 3.000, 4.000, 5.000 ..... something like that. Thanks for your help.

Hi @crazymumu

I think the issue is that you're using the less accurate ROS operating system "software" timer to measure the more accurate SAMD21 hardware one. The drift you're seeing is in the measuring timer, not the measured one, (despite the fact the ROS timer outputs nanosecond values).

In this context does PPS mean Pulse Per Second? Do you mean generating a 100ms pulse, delayed by a specified duration relative to some event that has happened?

Hi @MartinL , thanks for your reply.

I think the issue is that you’re using the less accurate ROS operating system “software” timer to measure the more accurate SAMD21 hardware one. The drift you’re seeing is in the measuring timer, not the measured one, (despite the fact the ROS timer outputs nanosecond values).

Thanks for your suggestions. May I ask what's the right way to measure the hardware timer, using micro() or millis() ?

In this context does PPS mean Pulse Per Second? Do you mean generating a 100ms pulse, delayed by a specified duration relative to some event that has happened?

Yes, PPS means Pulse Per Second. What you suggested code to generate PPS is actually good.

For example, the time generated PPS is 1619111810.656072616 s, but some sensor (at least our sonar does this) will only use 1619111810 to update their internal timer, but the truth is the sensor time is 0.656072616 later then the timer source (here is Arduino Zero). That's the why I am trying to generate PPS at the beginning at every second.

The other way is just set a constant time offset between sonar and other sensors. Then align them during the post-processing. But if there is a way to generate PPS at the beginning at every second, that will be great.

Hi @MartinL , could you check my questions when you have time. thank you so much!

Hi @crazymumu

My apologies for the delay in getting back.

If you have access to one, the easiest way is to use an oscilloscope, since this allows actual timings to be measured down to sub-microsecond level (or less) and is independent of the microcontroller itself.

Forgive me, but I don't understand what, "PPS is 1619111810.656072616 s" means? Are we talking about seconds or nanoseconds here?

Hi @MartinL , sorry for the late reply. I just finished my final project.

Sorry to confuse you. I made simple plots showing below.

For the plot (1) Actual PPS Generation: the red time is the actual PPS generation time. It will used to update the sensor's timer. For example, the time "1.101345" sent to sensor, but sensor only get "1.000000" to update timer, all the value after decimal will be ignored. Obviously, the sensor timer will always 0.101s behind Arduino.

For the plot(2) Ideal PPS Generation: if the PPS generated at the red time, which is the ideal exactly the beginning of each second. Then the time is good for sensor.

Is that possible to configure PWM to output like plot(2)? Thanks for your help.

There is more information on this link: How to set PWM frequency to 1 Hz on an UNO - #10 by Railroader

This topic was automatically closed 120 days after the last reply. New replies are no longer allowed.