change thread priority from a timer callback

Discussions and support about ChibiOS/RT, the free embedded RTOS.
tridge
Posts: 141
Joined: Mon Sep 25, 2017 8:27 am
Location: Canberra, Australia
Has thanked: 10 times
Been thanked: 20 times
Contact:

Re: change thread priority from a timer callback

Postby tridge » Mon May 07, 2018 7:48 am

faisal wrote:Wow, that's a fantastic amount of data.

yes, we're pushing the F427 pretty hard
Do you have 2 interrupts, one at 8k and the other at 1k - and in each interrupt you perform spi polled exchanges? Do you use DMA?

We do use DMA for all SPI transfers. We also use the device FIFOs though, and for the IMUs running at 8kHz sample rate we read multiple samples at once. We just need to make sure we read fast enough to ensure the FIFO doesn't overflow (exact FIFO depth varies between IMU submodels, but typical depth is at least 20 samples).
I'm guessing the DMA interrupt overhead may not be worth it for dozens of bytes of data.

It is well worth it to use the DMA, especially when reading multiple samples at once. An SPI transfer of 14 bytes at 8MHz takes around 16usec, whereas the interrupt costs a fraction of a microsecond.
I'm working on something similar and was wondering what would be the most efficient approach - I figure you must have figured that out already :)

we've found that "thread per bus" works really well as model for ArduPilot.
Also note that we run the system clock at 1MHz in tickless mode.
Cheers, Tridge

tridge
Posts: 141
Joined: Mon Sep 25, 2017 8:27 am
Location: Canberra, Australia
Has thanked: 10 times
Been thanked: 20 times
Contact:

Re: change thread priority from a timer callback

Postby tridge » Mon May 07, 2018 7:52 am

Giovanni wrote:Anyway, I will look into implementing priority change. It will be done in trunk but you can back-port the code in any version, the scheduler has been stable for years now.

thank you. We are planning on re-basing on ChibiOS trunk soon anyway.
Also, don't prioritize this on our account. After your first answer I went back and re-worked how we do the priority changes so that they always happen from the thread that needs to change. I realized that we do have a natural point in the flow of the code where we know that we've done the flight critical parts of the main loop and we're about to start on the intensive maths (the EKF update). By hooking the priority change into that point we get exactly what we need without having to change priority from a callback.
So it might be nice to implement this for completeness for other users, but we will stick to the new approach now.
Cheers, Tridge

tridge
Posts: 141
Joined: Mon Sep 25, 2017 8:27 am
Location: Canberra, Australia
Has thanked: 10 times
Been thanked: 20 times
Contact:

Re: change thread priority from a timer callback

Postby tridge » Mon May 07, 2018 7:58 am

FXCoder wrote:BTW are you using classic tick based or tickless ChibiOS mode?

On the F4 we use tickless mode, with a 1MHz system clock.
I should also note that we have a small optimization to the tick conversion macros for the specific case of a 1MHz clock:
https://github.com/ArduPilot/ChibiOS/co ... e184855f1a
that improves things in two ways:
- a bit less maths when converting ticks to and from microseconds
- avoids the overflow issues with the conversion calculations
I do remember reading somewhere that someone has previously reported problems with using a 1MHz system clock in tickless mode. We've found it great, and it really helps reduce timing jitter. I can't find the previous place where I read about problems with it now. Does anyone remember that issue?

User avatar
FXCoder
Posts: 384
Joined: Sun Jun 12, 2016 4:10 am
Location: Sydney, Australia
Has thanked: 180 times
Been thanked: 130 times

Re: change thread priority from a timer callback

Postby FXCoder » Mon May 07, 2018 2:54 pm

Hi Andrew,
Cool in Sydney tonight... probably a bit cooler in Canberra :-)

Your F427 certainly has its work cut out for it!

I'm working on an airborne project as well albeit balloon oriented based on an F413.
We're receiving different traffic to you (amateur radio stuff) but do give the F413 a hiding (in bursts) decoding packets from raw radio PWM through a DSP chain (fixed point variety) and then off into packet decoding, repeating, etc.
Silicon labs radio, GPS is UBLOX, BME280 for environment and an OV5640 camera for still capture.

I do remember reading somewhere that someone has previously reported problems with using a 1MHz system clock in tickless mode. We've found it great, and it really helps reduce timing jitter. I can't find the previous place where I read about problems with it now. Does anyone remember that issue?


These might be the threads you were refering to...
viewtopic.php?t=2280
viewtopic.php?t=2537

Cheers,

Bob

User avatar
Giovanni
Site Admin
Posts: 14444
Joined: Wed May 27, 2009 8:48 am
Location: Salerno, Italy
Has thanked: 1074 times
Been thanked: 921 times
Contact:

Re: change thread priority from a timer callback

Postby Giovanni » Mon May 07, 2018 5:18 pm

The 2nd thread is quite interesting, all the youth problems with tick-less mode. Those were 4 o 5 distinct problems overlapping, each one with a tiny probability to happen.

I don't remember about problems at 1MHz except for incorrect "delta" settings.

Giovanni

andypiper
Posts: 65
Joined: Sat Oct 24, 2020 5:21 pm
Has thanked: 5 times
Been thanked: 4 times

Re: change thread priority from a timer callback

Postby andypiper » Fri Feb 19, 2021 5:23 pm

Giovanni wrote:Hi,

I wrote a tentative implementation of a function able to change another thread priority. I am not sure it is fully correct because not all cases have been carefully considered.

Code: Select all

/**
 * @brief   Changes another's thread priority level.
 * @note    The function returns the real thread priority regardless of the
 *          current priority that could be higher than the real priority
 *          because the priority inheritance mechanism.
 *
 * @param[in] tp        pointer to the thread
 * @param[in] newprio   the new priority level of the running thread
 * @return              The old priority level.
 *
 * @iclass
 */
tprio_t chThdSet2PriorityI(thread_t *tp, tprio_t newprio) {
  tprio_t oldprio;

  chDbgCheckClassI();

  chDbgCheck((tp != NULL) && (newprio <= HIGHPRIO));

#if CH_CFG_USE_MUTEXES == TRUE
  oldprio = tp->realprio;
  if ((currp->prio == tp->realprio) || (newprio > tp->prio)) {
    tp->prio = newprio;
  }
  tp->realprio = newprio;
#else
  oldprio = tp->prio;
  tp->prio = newprio;
#endif

  switch (tp->state) {
  case CH_STATE_READY:
    (void) chSchReadyI(queue_dequeue(tp));
    break;
#if CH_CFG_USE_SEMAPHORES_PRIORITY == TRUE
  case CH_STATE_WTSEM:
    queue_prio_insert(queue_dequeue(tp), &tp->u.wtsemp->queue);
    break;
#endif
#if CH_CFG_USE_MESSAGES_PRIORITY == TRUE
  case CH_STATE_SNDMSGQ:
    queue_prio_insert(queue_dequeue(tp), &tp->msgqueue);
    break;
#endif
  case CH_STATE_WTMTX:
    queue_prio_insert(queue_dequeue(tp), &tp->u.wtmtxp->queue);
    break;
  default:
    /* All remaining states do not require queue handling.*/
    chDbgAssert(tp->state < CH_STATE_FINAL, "invalid state");
    break;
  }

  return oldprio;
}


Do not assume it is final but you can include it in your code anyway.

Giovanni


Hi Giovanni, we are indeed using this in our code, but prio has disappeared from thread_t in 20.3.x so it no longer works when we try to upgrade - can you recommend a replacement?

Thanks
Andy

User avatar
Giovanni
Site Admin
Posts: 14444
Joined: Wed May 27, 2009 8:48 am
Location: Salerno, Italy
Has thanked: 1074 times
Been thanked: 921 times
Contact:

Re: change thread priority from a timer callback

Postby Giovanni » Fri Feb 19, 2021 5:27 pm

Hi,

Just replace any reference to "prio" with "hdr.pqueue.prio".

Giovanni

andypiper
Posts: 65
Joined: Sat Oct 24, 2020 5:21 pm
Has thanked: 5 times
Been thanked: 4 times

Re: change thread priority from a timer callback

Postby andypiper » Fri Feb 19, 2021 6:48 pm

Giovanni wrote:Hi,

Just replace any reference to "prio" with "hdr.pqueue.prio".

Giovanni


Thanks!


Return to “ChibiOS/RT”

Who is online

Users browsing this forum: No registered users and 3 guests