The sPRUnal chord of Beaglepilot continued

In my last blog post i discussed how PRU can be useful in the development of Beaglebone-Linux-Ardupilot based Autopilot. In this blog post i'll be sharing how it is being implemented presently on beaglepilot. PRU-PWM (PWM generation using PRU) is in development stage and there are many possibilities to make it work at its best.

Implementation of PWM generation using PRU is based on the work by Pantelis Antoniou on testpru & driver to go along with it. Initially I worked with AM335x PRU Package for uploading the firmware in binary format. After seeing the power and ease of usage of Pantelis's infrastructure I moved to implement it inside Ardupilot HAL. Pantelis's infrastructure works on the basis of upcalls and downcalls. All three cores constantly keep in touch by raising signals to each other so that they can inform each other what to do next, while data exchange occurs via shared memory. Also sysfs interface is provided so that userspace can communicate with PRUs.

All was perfect until the measurement of time taken for writing PWM value for each channel was found out to be between 500-1000us, which is about 20 times higher than required. The bottleneck in the whole apparatus was sysfs interface, opening, writing and closing of files took a of time. So we had to let go of sysfs interface and thus only purpose of driver was to load the firmware. Another thing we need to let go of is the rproc and virtio implementation done by Pantelis which was unnecessary for Ardupilot and consumed one extra PRU core. So final implementation is as follows: Firmware is loaded to PRU, All pins required as PWM channel (which actually are R31 bits as explained in previous post) are declared to be used using cape manager overlays for now, but will be declared under device tree in future. Ardupilot (Userspace) communicates and exchanges data via placing data directly into Shared Memory via mmap, no signals are raised because communication is between only two devices and simplex type(PRU1 and ARM, PRU0 is not in picture now and will be serving other purposes like PPM reader or sensor data time stamper etc). Data is placed into the shared memory along with access flag, application on both side poll for the access and change the value of access flag data when they have placed it into there local memory(in PRUs case) or writing into shared memory is complete(in ARMs case). Another task in this development is to create an independent firmware loader either in userspace or in kernel space as driver. The firmware loader should be able to load elf files into the PRU. For now Pantelis's driver is handling that task, until everything is going well we can turn a blind eye on independent firmware loader's development.

All in all after making these changes, PWM write time for each channel reduced to 10us with some occasional measured time of 500us-1000us, the reason for which is yet unknown. It would be great if you all can share your views on this implementation.

Regards,

Siddharth Bharat Purohit

 

E-mail me when people leave their comments –

You need to be a member of diydrones to add comments!

Join diydrones

Comments

  • Have you looked into the machinekit build for the beaglebone? It is really meant for true real-time machine control. It is orientated in the cnc/3d printer side of things at the moment, but they are doing great things getting minimalist  real-time kernels running smooth with full use of the pru units. As you can imagine the timing on cnc machines must not vary so the stepper pulse generation is all handled real-time. http://www.machinekit.io/ is the home page but most all discussion is carried out on the mailing list  https://groups.google.com/forum/#!forum/machinekit

    I have 2 beagle bones and will be watching with great interest.

    Machinekit • Moves. Controls. Things.
  • Please share if you have any suggestions.

  • Hi Roberto, Beaglepilot team had a voice chat discussion today and during that it was suggested by Andrew that we use asynchronous method of communicating with PRU, meaning no more sleeps to synchronise, just simple exchange of data. So, I will move forward make changes accordingly.

  • Moderator

    Hi Sis in skype i send to you that in other project i saw that usleep is not RT function and it served by interrupt when the processor is free ... not at exact time ... you reply me that try to use hal micros ... but that is RT function ? 

  • Developer

    Hi Sid, I'd expect the occasional high time to be because a task switch occurs and something else runs for that time. That is actually OK, as the CPU is still doing something productive.

    If you want to see if this is indeed the issue then use hal.scheduler->suspend_timer_procs() and hal.scheduler->resume_timer_procs() around the code that writes to the shared memory. If the task switch is due to an ardupilot thread (eg. timer) then that should avoid it. This would be for testing only though, as we actually don't mind timers stealing some CPU from the main thread.

    It also could be some other OS task stealing some time. That is harder to track down.

    10us is certainly a huge improvement! It is still a little higher than I expected though. It may be granularity of timer measurement. What time do you measure if you do nothing? ie. just measure an empty function call. That will give you some idea of the cost of measuring time.

    Cheers, Tridge

  • Sorry for not being clear on that point, by measured time i mean time took to write PWM values to shared memory. I calculated it using hal.scheduler->micros to measure execution time of hal.rcout->write. Obviously it doesnot provide us with total time it took to reflect PWM pulse on the pins after being commanded, but gives a rough idea of how fast userspace application is.
  • Moderator

    Hi Sid

    i don't understand exactly your problem ... start from begin .

    You need to generate on Servo / Esc output a signal from 1000 us to 2000 us with a frequency update of 490 hz

    When you told "occasional measured time is of 500us - 1000us what mean ? That you see on oscilloscope a stop of PWM out of 500 - 1000 uS ? Or What ? 

This reply was deleted.