NASA competition - suitability of AQ6 or M4

Info and discussion about the original AQ v6 flight controller

Re: NASA competition - suitability of AQ6 or M4

Postby JussiH » Wed Oct 01, 2014 1:22 pm

Pls send me a PM to arrange the HW

Jussi
JussiH
 
Posts: 2103
Joined: Thu Jun 21, 2012 9:25 pm

Re: NASA competition - suitability of AQ6 or M4

Postby Max » Wed Oct 01, 2014 9:36 pm

Hi Florent,

flomartel wrote: So, do you recommend the STM32F4Discovery with STM32F407VG processor model?

I only know of one http://www.digikey.com/product-search/e ... 1t1-VQ16-c

Great question about the M4 vs. the AQ6 w/DIMU. I don't know enough yet about the differences (essentially same source code?) to make a judgment call, so I'm tempted to turn the question back to you. I'm candidly struggling to find information about the hardware and interfaces besides a few pictures and diagrams lying around... So, which one do you think would be most suitable given what you know about my project?


Same exact source code except for the board definition files (parameters to account for hw differences). I'm not a hardware expert, but I don't see what advantages the M4 would have for your needs. Seems like you want all the I/O ports you can get, and especially the USART-capable ones. I'm not sure what advantages the M4's small size, USB, onboard brushed drivers, and onboard radio chip would have for you. The micro size quads do make a great (safe/cheap) testing platform. But if you already have to go beyond that size due to other hardware, the FC board size might not matter.

Then there's practical matters to consider, for example the M4 needs to be turned on via a momentary contact (by default this is a tiny button switch on the edge of the board), vs. the v6 which will just power up as soon as power is applied.

Random question: has there been any discussion about interfacing the ESC32v3 with other autopilots? I know that would require code changes on those autopilots, but I believe some could be convinced by some of its features...


They can already run with any FC via PWM. I have not heard of any other projects implementing the CAN interface.

Cheers,
-Max
Max
 
Posts: 2814
Joined: Mon Aug 13, 2012 9:45 pm
Location: Near Ithaca, NY, USA

Re: NASA competition - suitability of AQ6 or M4

Postby Kisssys » Thu Oct 02, 2014 1:58 am

I agree with Max on the M4, the AQ6 is better for your purpose. The AQ7 is probably the perfect choice with a Gumstix to run your algorithm but that's all very virgin ground.
Steve
Kisssys
Kisssys
 
Posts: 1340
Joined: Sat Jun 23, 2012 9:23 pm

Re: NASA competition - suitability of AQ6 or M4

Postby flomartel » Fri Oct 03, 2014 7:56 am

Thank you all for the information provided! I will need some more time to study it...
flomartel
 
Posts: 13
Joined: Thu Jun 05, 2014 4:31 pm
Location: MN, USA

Re: NASA competition - suitability of AQ6 or M4

Postby flomartel » Fri Oct 10, 2014 8:09 am

I'm starting to setup my build environment and will soon attempt to compile and upload an unmodified firmware onto the AQ at first.

On a somewhat separate note, I am also looking at possibly implementing an AGL sensor with the AQ. The obvious functionalities are precision landing and flying at a set altitude above ground. Has any of this work been done for a sonar/lidar?

I noticed a separate UKF has been added lately for the altitude ("alt_ukf") that uses measured downward acceleration integrated over time for the prediction step and measured barometric pressure converted to an altitude value for the correction step. The resulting ALT_POS and ALT_VEL state estimates are used when gpsData.hAcc (horizontal accuracy estimate contained in the NAV-POSLLH uBlox message) > 0.8 meters. Otherwise, UKF_PRES_ALT (the 17th state estimate - navUkfData.x[16] - of the nav filter) and UKF_VELD (the 3rd state estimate) are used since USE_PRES_ALT is set to 1 by default.

So, what I understand from this is that when the reported horizontal (why not vertical?) accuracy of the GPS measurements is insufficient, ALT_POS and ALT_VEL are used, otherwise UKF_PRES_ALT and UKF_VELD are used. I looked at the equations and the state estimates are calculated a little differently between the two filters (initial values are the same), but I’m struggling to understand why. For example, barometer bias is taken into account in the altUkfTimeUpdate but not the accelerometer bias. Another example is that measured downward acceleration integrated over time for the prediction step (“acc”) is divided by two in the alt UKF but not in the nav UKF. More fundamentally, I don’t get why there’s a separate alt UKF coded for when GPS performance is degraded (or in a GPS denied environment) since UKF_VELD is not determined using GPS height anyways. Is it linked to the use of “navData.presAltOffset” which adjusts pressure altitude for waypoint navigation when there’s a good GPS fix?

I’m not intimately familiar with UKFs, and I haven’t taken the time to reconstruct all the equations, so I may be a little over my head. I do want to learn how it all works...

How were the process and measurement noise values for the altitude and vertical velocity for both the alt and nav UKFs determined (there’s a bunch of them)? I’m trying to find what kind of specs/measurements I would need to find out about the sensor I would like to integrate to determine some decent noise values to use.
flomartel
 
Posts: 13
Joined: Thu Jun 05, 2014 4:31 pm
Location: MN, USA

Re: NASA competition - suitability of AQ6 or M4

Postby bn999 » Fri Oct 10, 2014 11:19 am

flomartel wrote:On a somewhat separate note, I am also looking at possibly implementing an AGL sensor with the AQ. The obvious functionalities are precision landing and flying at a set altitude above ground. Has any of this work been done for a sonar/lidar?


I've done some work at various times with AGL sensors. They are difficult to integrate into the existing UKF as they depend on knowledge of the topography which you are flying over for which there is not way to predict. So you end up with measurements which contradict the timestep updates as you pass over terrain which is changing over time. Not a problem over flat ground, but otherwise... Also, sonar has a lot of non-Gaussian noise which requires pre-filtering which I found messy. Lidar might work out better.

flomartel wrote:For example, barometer bias is taken into account in the altUkfTimeUpdate but not the accelerometer bias.


Actually the bias used in that function *is* ACC bias.

flomartel wrote:Another example is that measured downward acceleration integrated over time for the prediction step (“acc”) is divided by two in the alt UKF but not in the nav UKF.


I don't see what you are referring to. Can you quote line numbers?

flomartel wrote:More fundamentally, I don’t get why there’s a separate alt UKF coded for when GPS performance is degraded (or in a GPS denied environment) since UKF_VELD is not determined using GPS height anyways. Is it linked to the use of “navData.presAltOffset” which adjusts pressure altitude for waypoint navigation when there’s a good GPS fix?


All states can be influenced by all measurements if there is determined to be any co-variance during operation. The main UKF was tuned with the intent that it was to be used with very good GPS reception. When this measurement is not available or severely denigrated, the first thing to drift are the velocity estimates. Horizontal is not so important, but people expect the relative altitude position and necessarily the vertical velocity to be perfect even without GPS. After all, we do have a barometer. So, I tuned up a small auxiliary UKF to handle just vertical position, velocity and ACC bias for these times. Worked pretty well, so I included it in the system.

flomartel wrote:How were the process and measurement noise values for the altitude and vertical velocity for both the alt and nav UKFs determined (there’s a bunch of them)? I’m trying to find what kind of specs/measurements I would need to find out about the sensor I would like to integrate to determine some decent noise values to use.


You have successfully identified the key component missing yet necessary to get any KF type filter to work well. If you ask an academic, they will tell you that you simply have to determine the actual variance for each process & measurement term and you will have all you need for a well tuned KF. In reality, that does not work very well.

For a simple filter, you can usually tune it by hand (as I did with the new ALT UKF.) But, with more complex filters, it becomes nearly impossible. Recognizing this early on, I created an offline process which takes ground truth data and scores the filters estimates made during a flight based on the recorded measurements. The scoring is used by a parameter estimation UKF which estimates the ideal variances and other tunable parameters used by the onboard UKF.

So, if you want to add a new sensor or state to the UKF, to get optimal performance, this automated tuning would have to be re-run. Not a simple task as it requires some number of example flights showing all conditions that the filter would likely encounter and quite a bit of CPU time to run the simulations. And you have to make sure that your ground truth data has enough visibility on the system to constrain most of the predictions. A Vicon type system would make the job much easier, but I do not have such a tool - and they don't work outside very well.
bn999
 
Posts: 1559
Joined: Thu Jun 21, 2012 11:40 pm

Re: NASA competition - suitability of AQ6 or M4

Postby flomartel » Sat Oct 11, 2014 12:27 am

Actually the bias used in that function *is* ACC bias.

Got it! It makes more sense now what as to what ALT_BIAS_NOISE refers to...

I don't see what you are referring to. Can you quote line numbers?

Maybe I don't quite get how it's done but I'm comparing these two snippets of code
Lines 19-20 of alt_ukf.c
Code: Select all
out[ALT_STATE_VEL*n + i] = in[ALT_STATE_VEL*n + i] + (acc * dt) + (noise[ALT_NOISE_VEL*n + i] * dt);
out[ALT_STATE_POS*n + i] = in[ALT_STATE_POS*n + i] - (in[ALT_STATE_VEL*n + i] * dt) - (acc * dt * dt * 0.5f);
and lines 307 and 286 of nav_ukf.c
Code: Select all
out[UKF_STATE_VELD*n + i] = in[UKF_STATE_VELD*n + i] + acc[2] * dt + noise[UKF_V_NOISE_VELD*n + i];
out[UKF_STATE_PRES_ALT*n + i] = in[UKF_STATE_PRES_ALT*n + i] - in[UKF_STATE_VELD*n + i] * dt;

I mischaracterized the difference in my previous post, but essentially (acc * dt^2) / 2 shows up in the alt UKF but not in the nav UKF, and I was wondering why the difference...

Thanks for your interesting comparison of AGL sensor technologies. It prompted me to look briefly at the code related to the optical flow sensor + sonar sensor (using PX4FLOW?) and the way you handled the sonar data. I think this is a good example and would serve as a nice basis for any other AGL sensor integration work. Interesting to see you used mavlink to interface with the sensor and intrigued as to why you used the averaged ground distance measurements for the altitude state estimates. Why is that?

I agree with you that sonar is difficult to work with since the measurements are subject to vibrations, acoustic noise, pressure differences, etc., but you did it! I saw a video on youtube sometime ago of the result in flight which seemed satisfactory but admittedly the ground seemed relatively flat (it was a wooded area with trees if I recall correctly). How would you characterize the flight tests performed with the PX4FLOW?

So, if you want to add a new sensor or state to the UKF, to get optimal performance, this automated tuning would have to be re-run.

Is that what you have done for the nav UKF in the past? Sounds inconvenient if it has to be done for each variation of sensor suite and/or sensor combination. However, when the sonar is "active," the GPS altitude measurements (among others) are ignored and the UKF_POSD state estimate becomes altitude above ground, which I think alleviated a lot of the issues you're talking about, since you didn't add a new state to the UKF but cleverly recharacterized that state as altitude above ground. Process noises can remain the same since there's none affecting UKF_POSD (see line 283 of nav_ukf.c).

Do you have plans to integrate a lidar or another type of AGL sensor with the AQ? Besides the advantages I already mentioned, do you see others in using an AGL sensor?
flomartel
 
Posts: 13
Joined: Thu Jun 05, 2014 4:31 pm
Location: MN, USA

Re: NASA competition - suitability of AQ6 or M4

Postby bn999 » Sat Oct 11, 2014 1:56 pm

flomartel wrote:Maybe I don't quite get how it's done but I'm comparing these two snippets of code
Lines 19-20 of alt_ukf.c
Code: Select all
out[ALT_STATE_VEL*n + i] = in[ALT_STATE_VEL*n + i] + (acc * dt) + (noise[ALT_NOISE_VEL*n + i] * dt);
out[ALT_STATE_POS*n + i] = in[ALT_STATE_POS*n + i] - (in[ALT_STATE_VEL*n + i] * dt) - (acc * dt * dt * 0.5f);
and lines 307 and 286 of nav_ukf.c
Code: Select all
out[UKF_STATE_VELD*n + i] = in[UKF_STATE_VELD*n + i] + acc[2] * dt + noise[UKF_V_NOISE_VELD*n + i];
out[UKF_STATE_PRES_ALT*n + i] = in[UKF_STATE_PRES_ALT*n + i] - in[UKF_STATE_VELD*n + i] * dt;

I mischaracterized the difference in my previous post, but essentially (acc * dt^2) / 2 shows up in the alt UKF but not in the nav UKF, and I was wondering why the difference...


Technically, the term should exist on both, but it really does not make much of a difference so I often just leave it out to save CPU cycles. With a dt of (1/200), the difference is only (acc * 1.25e-5) and with low acceleration can be safely dropped.

flomartel wrote:Thanks for your interesting comparison of AGL sensor technologies. It prompted me to look briefly at the code related to the optical flow sensor + sonar sensor (using PX4FLOW?) and the way you handled the sonar data. I think this is a good example and would serve as a nice basis for any other AGL sensor integration work. Interesting to see you used mavlink to interface with the sensor and intrigued as to why you used the averaged ground distance measurements for the altitude state estimates. Why is that?


Look closer at the code. Multiple measurements are being received and summed, and UKF updates are made at a lower frequency.

flomartel wrote:I agree with you that sonar is difficult to work with since the measurements are subject to vibrations, acoustic noise, pressure differences, etc., but you did it! I saw a video on youtube sometime ago of the result in flight which seemed satisfactory but admittedly the ground seemed relatively flat (it was a wooded area with trees if I recall correctly). How would you characterize the flight tests performed with the PX4FLOW?


It took a lot of finessing, but eventually I got it to perform as I wanted in a controlled test. I hijacked the GPS measurements and states for the test so I did not have a fully integrated solution. The tests with the PX4FLOW sensor were just a proof of concept. If I were to do it for real, I'd re-tune the UKF. But, that would take a very precise ground (pun :) ) truth data probably having to come from a vision motion capture system.

flomartel wrote:Do you have plans to integrate a lidar or another type of AGL sensor with the AQ? Besides the advantages I already mentioned, do you see others in using an AGL sensor?


No specific plans. I'm instead concentrating on pure vision based navigation, but that won't be helpful to you any time soon as there is a lot of work yet to be done.
bn999
 
Posts: 1559
Joined: Thu Jun 21, 2012 11:40 pm

Re: NASA competition - suitability of AQ6 or M4

Postby zhlearnaq » Thu Dec 18, 2014 2:04 pm

hello,
Could anybody tell me the frequency of the attitude calculation - the value of AQ_OUTER_TIMSTEP? Is it a fixed value?
zhlearnaq
 
Posts: 43
Joined: Wed May 14, 2014 10:47 am

Re: NASA competition - suitability of AQ6 or M4

Postby zhlearnaq » Thu Dec 18, 2014 2:05 pm

hello,
Could anybody tell me the frequency of the attitude calculation - the value of AQ_OUTER_TIMSTEP? Is it a fixed value?
zhlearnaq
 
Posts: 43
Joined: Wed May 14, 2014 10:47 am

PreviousNext

Return to AutoQuad 6 Flight Controller

Who is online

Users browsing this forum: No registered users and 1 guest