programming question

131 views
Skip to first unread message

Roby

unread,
Nov 5, 2019, 7:14:48 AM11/5/19
to uavdevboard
Hello Friends,


Looking at the old MatrixNav code, I realized that the interrupts are stopped before every builtin_multiply function in order to guarantee no corruption of 32 bit data transfer occurs.

But in the new MatrixPilot code this has not been done. So how come you can confirm that this corruption will not happen anymore?

Thanks,
Roby

william premerlani

unread,
Nov 5, 2019, 6:41:53 PM11/5/19
to uavde...@googlegroups.com
Hi Roby,
We eventually realized that it was not necessary to stop the interrupts before every invocation of a builtin_multiply function because the code generated by the compiler for all  "c" source code is re-entrant.
Interestingly, we did discover that most of the routines in the vector-matrix library were not re-entrant, resulting in issues when they were called from multiple threads. I re-wrote the vector-matrix assembly language routines that we use so that they are now re-entrant. 
Here is a link to the new version of one of the routines:
Everything in the project is now re-entrant, so we can run with the interrupts always turned on.
Regarding data transfers, we can freely transfer 16 bit data between different threads. However, some care is needed for 32 bit transfers. In that case we typically either use a flag to provide handshaking for a protected transfer of the data or use double buffering.
Best regards,
Bill


--
--
---
You received this message because you are subscribed to the Google Groups "uavdevboard" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/a8831a40-1a5b-4fa6-8485-7f9e0a5dd5ec%40googlegroups.com.

Roby

unread,
Nov 6, 2019, 2:09:06 AM11/6/19
to uavdevboard
Hi Bill,

Good to hear from you again. It is always great to see the founder participate all these years. By the way, what could be a good incentive to make this list re-active again. Any ideas?

Regarding your answer you said " In that case we typically either use a flag to provide handshaking for a protected transfer of the data or use double buffering". Can you please show me examples where in the code you used those two ideas.

Best Regards,
Roby
To unsubscribe from this group and stop receiving emails from it, send an email to uavde...@googlegroups.com.

william premerlani

unread,
Nov 6, 2019, 9:59:30 AM11/6/19
to uavde...@googlegroups.com
Hi Roby,

The processing of GPS data provides examples of double buffering and the use of flags.

While the GPS is sending data, the GPS interrupt driven thread parses incoming messages and stores data into temporary variables.
When a complete set of data is available, the values are transferred from the temporary variables into the variables used by computations in other threads.
For the EM406 or EM506 this is done by the following code:

Several flags are set to signal computations in other threads that the data that is needed is available:

The computations in other threads poll the flags and reset the flags and perform their calculations when the flags are set.
Here is a typical example of that:

Best regards,
Bill

Roby

unread,
Nov 7, 2019, 10:08:09 AM11/7/19
to uavdevboard
Hello Bill,

Below you mentioned that you changed the routines to make them re-entrant. Where can I find the original versions of the routines so that I could see the modifications. I could not find them in the MPLABX directory.

Thanks for your help.
Roby

On Tuesday, November 5, 2019 at 11:41:53 PM UTC, william premerlani wrote:
To unsubscribe from this group and stop receiving emails from it, send an email to uavde...@googlegroups.com.

william premerlani

unread,
Nov 7, 2019, 11:30:29 AM11/7/19
to uavde...@googlegroups.com
Hi Roby,
The original source code for the matrix-vector routines is in a subdirectory of the xc subdirectory. I am not sure what the exact path will be for your installation and you may or may not have to extract some zip files.
Anyway, on my machine the original source is under xc16/v1.35/src/lipdsp/asm. I am sure that if you look around a bit and possibly extract some zip files, you will find them.
The changes I made to the routines simply involved saving and restoring resources that were not already being preserved.
Also, I think there were some minor additions to the interrupt service routines to manage CORCON.
Best regards,
Bill

On Thu, Nov 7, 2019 at 10:08 AM Roby <roberts...@gmail.com> wrote:
Hello Bill,

Below you mentioned that you changed the routines to make them re-entrant. Where can I find the original versions of the routines so that I could see the modifications. I could not find them in the MPLABX directory.

Thanks for your help.

Roby

unread,
Nov 9, 2019, 7:07:59 AM11/9/19
to uavdevboard
Hi Bill,

Thanks, I found the routines.

I have another question regarding acceleration compensation in the earth frame. It seems that this a very promising improvement but Pete Hollands said that it was no more supported,


Is there any reason for that? I find it great not to  be concerned of the aerodynamic model of your aircraft and just concentrating on kinematics.

Best Regards,Roby

william premerlani

unread,
Nov 10, 2019, 10:26:24 AM11/10/19
to uavde...@googlegroups.com
Hi Roby,
Regarding the acceleration compensation method that you are referring to, further testing revealed that, without a magnetometer, the method was not "bullet proof". Without a magnetometer, under certain circumstances it could sometimes fail to "lock in" after takeoff, particularly if the initial yaw estimation error was large.
Although the method that we are using now is not as accurate as the method that you are referring to, it is more robust.
Furthermore, it does not need a GPS at all so it continues to operate in the event of GPS failure or for simple flight stabilization without a GPS.
Best regards,
Bill



--
--
---
You received this message because you are subscribed to the Google Groups "uavdevboard" group.
To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/c5be86af-0d1c-4f56-9ab3-a11483b87809%40googlegroups.com.

Roby

unread,
Nov 11, 2019, 11:43:22 AM11/11/19
to uavdevboard
Hi Bill,

Why will this method fail, taking into account that after takeoff there is a GPS fix. Maybe there is some unknown reason other than the initial yaw estimation error?

Regards,
Roby
To unsubscribe from this group and stop receiving emails from it, send an email to uavde...@googlegroups.com.

william premerlani

unread,
Nov 11, 2019, 12:28:02 PM11/11/19
to uavde...@googlegroups.com
Roby,
A math analysis that I performed for this method indicated that there were two solutions to an underlying nonlinear equation whenever a magnetometer is not used, one of them correct and one of them spurious, with a 180 degree error for yaw. Without a yaw reference, the 180 degree yaw error induced divergence in the pitch and roll computations. Whether or not that was the root cause, in fact one of our top test pilots, Ric, who was in the habit of pushing the envelope, reported a flight in which the computations diverged. At that point I withdrew the new method until I could make it robust. However, in the meantime I decided that I preferred a method that did not need a GPS at all since there were several users, including myself, that wanted to be able to fly without GPS.
Best regards,
Bill

To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/5c4665d3-8a89-465e-9835-e825b307512c%40googlegroups.com.

Roby

unread,
Nov 12, 2019, 11:05:09 AM11/12/19
to uavdevboard
Hi Bill,

I will try try to redo the math calculation to convince myself why the computation divergence happens.

Regarding flying without GPS, I suppose that you are using an estimated airspeed to calculate centrifugal acceleration? If this is the case, it will be no help in waypoint navigation?

Best Regards,
Roby

william premerlani

unread,
Nov 12, 2019, 11:58:54 AM11/12/19
to uavde...@googlegroups.com
Hi Roby,

Regarding centrifugal compensation without GPS, I figured out a way to approximately compensate for centrifugal acceleration without an airspeed estimate. All that is needed for a compensated estimate of a vertical reference is gyro and accelerometer signals. The method works quite nicely for fixed wing, it is both robust and reasonably accurate. It will not work for multi-rotor.

Obviously, without GPS it is not possible to do waypoint navigation, but it is still possible to perform attitude stabilization. Peter Hollands is using a GPS-less version for a free-flight hand launch unpowered glider that he built for his grand daughter.

Regarding the math for divergence of the GPS based centrifugal compensation, consider the case of no magnetometer and a large yaw estimation error. Take into account GPS latency and consider all values of roll and pitch attitude and moderate errors in roll and pitch estimation. The problem is that the GPS method provides only one reference vector. Two vectors are needed to perform gyro drift compensation. Convergence robustness will depend on how the second reference vector is computed and the details of the gyro drift compensation. The divergence loop passes through the proportional-integral gyro drift compensation feedback.

Best regards,
Bill

To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/5bc29713-b8d7-4eea-b198-da9f1767a052%40googlegroups.com.

william premerlani

unread,
Nov 12, 2019, 12:09:20 PM11/12/19
to uavde...@googlegroups.com
Roby,
Here is a link to a discussion of the centrifugal compensation method presently being used in MatrixPilot:
It includes a file that summarizes the math.
Best regards,
Bill
 

To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/5bc29713-b8d7-4eea-b198-da9f1767a052%40googlegroups.com.

Roby

unread,
Nov 13, 2019, 11:18:28 AM11/13/19
to uavdevboard
Hi Bill,

As always, a great paper. Thank you!

But you seem to neglect forward acceleration. Is this always acceptable especially in hand launched aircrafts?

Also, I assume that you are calling the derivative of the airspeed vector w.r.t the body frame as forward acceleration. Can this acceleration be considered a true acceleration? 
I am asking because airspeed has components in the ground frame if there is no wind. So deriving this vector w.r.t the ground frame can be interpreted as a true forward acceleration. 
Deriving w.r.t the body frame is something else.
 Am I missing something?

Best Regards,
Roby

william premerlani

unread,
Nov 13, 2019, 2:20:40 PM11/13/19
to uavde...@googlegroups.com
Hi Roby,

 Good questions, very perceptive.

When a GPS is available, Matrix Pilot accounts for forward acceleration, otherwise it does not.

During a hand launch, a combination of the "catapult launch" algorithm that we are using to respond to pitch error and the fact that the forward acceleration is transient, prevents the error from becoming too large. It can be shown that the error is proportional to the time integral of the acceleration, which of course is the launch speed, with a low proportionality constant. Peter has been able to use the GPS-less version of MatrixPilot for hand launches without much pitch error.

On the other hand, centrifugal acceleration can be sustained and must be compensated.

Regarding true acceleration, under constant wind conditions, the time rate of change of the ground velocity vector is equal to the time rate of change of the air velocity vector, because the time rate of change of the wind vector is zero.

However, that does not mean that the decomposition of the acceleration vector into components that are parallel (also known as forward acceleration) and perpendicular (also known as centrifugal acceleration) to the airspeed vector and to the ground speed vector are the equal, because the airspeed vector is not parallel to the ground speed vector when there is wind. The two decompositions are related by a rotation transformation. Since the accelerometer signals are measured in the body frame, what is needed for acceleration compensation is an estimate of the body frame accelerations: time rate of change of airspeed for the forward direction and the cross product of the airspeed vector with rotation rate vector for the perpendicular direction.

In the case of an aircraft flying with constant airspeed with a constant wind, the true forward acceleration in the body frame is zero, while the acceleration parallel to the ground track varies with time.

Best regards,
Bill

To unsubscribe from this group and stop receiving emails from it, send an email to uavdevboard...@googlegroups.com.
To view this discussion on the web, visit https://groups.google.com/d/msgid/uavdevboard/1e099734-f058-47ea-aeaf-e6444916fe0b%40googlegroups.com.

Roby

unread,
Nov 15, 2019, 12:44:55 PM11/15/19
to uavdevboard
Hello Bill,


Thanks for the clarification. 

I am trying to read the GPS latency code you have written but it seems that I need some theoretical background on it. Have you written any demonstration notes for this topic?

Best Regards,
Roby

Roby

unread,
Nov 21, 2019, 10:03:18 AM11/21/19
to uavdevboard
Hello Bill,

It is very appreciated if you could give a brief discussion of the code snippet related to GPS latency. What I understood is some kind of interpolation between three points, taking into consideration angular velocities during turns. But the details are still vague.

Best Regards,
Roby

william premerlani

unread,
Nov 21, 2019, 5:41:04 PM11/21/19
to uavde...@googlegroups.com
Hi Roby,

Thanks for the question.

Regarding the present version of compensation for GPS latency I offer the following brief explanation:

The primary information used for instantaneous speed, position and attitude estimation are computations based gyro and accelerometer signals. In a secondary computation, GPS information is merged with those sources to prevent accumulation of error due to time integration of small biases. Without compensation for GPS latency, there would be biases in the final estimates of velocity and position. Because the accelerometers and gyros provide the main source of information, the demands on the GPS latency compensation are not too great.

The team tried to determine the dynamics of the GPS latency for the various models of GPS that were employed by our users. Along the way, we discovered sources of latency in the MatrixPilot code, and eliminated them. We also discovered that the major contribution to latency in several of the models, especially the EM406 and EM506, was a simple communications delay of one set of samples.

So, what is needed is an algorithm that compensates for a pure one sample latency. In general, that is not possible to do with sampled data for the general case. However, all we really need to do is to compensate for bias during either straight line flight or during a turn. In that case you can do a geometrical analysis in what I liked to call "polygonal analysis" to determine the corrections based on changes the angles and positions. I no longer have the sketches, but you can work it out from geometry. The result is a two step process.

The first step is the computation of certain differences:


Then, based on the geometry of the polygons formed by samples of the GPS data, adjustments are made to the raw data.


Best regards,
Bill
Reply all
Reply to author
Forward
0 new messages