paparazzi-devel
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

Re: [Paparazzi-devel] Fwd: ahrs selection


From: Felix Ruess
Subject: Re: [Paparazzi-devel] Fwd: ahrs selection
Date: Mon, 21 Oct 2013 16:52:31 +0200

Hi Jorge,

Please find my airframe attached to this email. And yes, I am using the CHIMU as AHRS. Is there a way to configure the software or the airframe file to filter the vibrations read by my CHIMU? 

Not with the current ahrs_chimu module. I really don't know anything about the CHIMU, maybe it has some parameters that could be set...
Maybe Christophe (who added/wrote the CHIMU driver/wrapper) knows...

One other possibility would be to only use the CHIMU as an IMU and do the actual attitude estimation using e.g. the ahrs_int_cmpl_quat algorithm in Paparazzi again.
Doesn't look like there is a wrapper module ready for that so far though...

I also found in previous posts that the behavior due to vibrations I am experiencing with my CHIMU is called drifting. However I didn't find any solutions posted.

As long as the attitude estimation is done inside the CHIMU, there is not much you can do on the Paparazzi side (except maybe configure the chimu differently if that is possible).

Cheers, Felix 


Begin forwarded message:

From: Jorge Pantoja <address@hidden>
Date: 18 de octubre de 2013 18:33:21 GMT-5
To: "address@hidden" <address@hidden>

Subject: Re: [Paparazzi-devel] ahrs selection
Reply-To: address@hidden

Dear all,


Please find attached my airframe file. If you uncomment the line    <subsystem name="ahrs" type="int_cmpl_quat" /> and Build the program you will see the errors from my previous email. I read on the CHIMU manual (http://www.ryanmechatronics.com/public_files/user_manuals/modules/CHIMU/UM1000_CHIMU_User_Manual_REV_E.pdf) that it comes with a Quaternion and Euler estimators but it seems like these filters are not working with the ones available in Paparazzi.



Best Regards,
Jorge


On Fri, Oct 18, 2013 at 4:37 PM, Jorge Pantoja <address@hidden> wrote:
Hello guys,


Thank you very much for your explanations. Can you please show me how to implement the software filtering using the int_cmpl_quat method? I mean, in what part of my airframe file should I include it?

I am using a CHIMU (on the SPI port) with a Yapa2. My airframe is a 2 meter wingspan Telemaster with a OS 61 engine.

I did as explained in the wiki:

  <firmware name="fixedwing or rotorcraft">
     ...
    <subsystem name="ahrs" type="int_cmpl_quat"/>
  </firmware>
 
  <section name="AHRS" prefix="AHRS_">
    <define name="H_X" value=" 0.51562740288882"/>
    <define name="H_Y" value="-0.05707735220832"/>
    <define name="H_Z" value=" 0.85490967783446"/>
  </section>

But I am getting the following errors and warnings when building the code:

<command-line>:0:0: warning: "AHRS_TYPE_H" redefined [enabled by default]
modules/ins/ins_module.h:63:19: warning: redundant redeclaration of 'ins_roll_neutral' [-Wredundant-decls]

ahrs_int_cmpl_quat.c:(.text.ahrs_init+0x0): multiple definition of `ahrs_init'
ahrs_int_cmpl_quat.c:(.text.ahrs_align+0x0): multiple definition of `ahrs_align'
ahrs_int_cmpl_quat.c:(.text.ahrs_propagate+0x0): multiple definition of `ahrs_propagate'



And also I would like to apply the low pass filter to help with my vibrations problem but I don't know where or how to apply it on my airframe file. On the other hand, I noticed that I have defined <define name="ALT_KALMAN"/> on my airframe file, but I don't know how to properly use it. Can you please give me some help with this?


Best Regards,
Jorge


On 18/10/2013, at 12:53, Markus Bina <address@hidden> wrote:
Hi Loic,I


Many thanks!

Could you add some version info or the commit (link), eg. instead of "New in master"?

Cheers,
    Markus

Am 18.10.2013 18:41, schrieb Loic Drumettaz:

Hi,

I just added some info on the wiki about int_cmpl_quat new features in master.

Loic

Le 18 oct. 2013 16:59, "Felix Ruess" <address@hidden> a écrit :
Hi Refik,

the question of which filter is better is not easy to answer. This strongly depends on your needs and your setup (airframe, IMU, frequency, vibrations, etc.).
Also float_dcm is implemented in float and int_cmpl_quat (mostly) in fixed point and the latter should hence be more efficient. While you can run float_dcm at 60Hz for a fixedwing on a board without FPU, I don't think it would run at 512Hz (which is not a problem for int_cmpl_quat).
Unfortunately I can't provide a quantitative comparison of the two...

But since you were experiencing problems with float_dcm in your setup, I would recommend to test int_cmpl_quat.
(Of course first try better mechanical damping as others mentioned before).

Regarding the "correction" by accelerometer measurements in such simple attitude only filters:
They assume that (on average) you measure only acceleration due to gravity, which in turn gives you roll/pitch measurements.
Of course this is not quite true while you accelerate (includes flying circles!).
For quadrotors this is not quite as bad as for fixedwings, since the assumption that these trajectory accelerations average out to zero is good enough in most cases.
But fixedwings can't hover and instead have to constantly fly circles if you want to "stay" at one spot. This means a constant trajectory acceleration to keep you on the circle!
Now for fixedwings these filters use the GPS speed together with the assumption that you are flying forward or a coordinated turn (no significant side slip) to compensate for this centrifugal force.
For int_cmpl_quat this is enabled with AHRS_GRAVITY_UPDATE_COORDINATED_TURN (which is set by default if you use the fixedwing firmware).

Now regarding gravity_heuristic_factor in int_cmpl_quat:
This heuristic is meant to temporarily decrease the "correction" from the accelerometer measurement while you have trajectory accelerations by scaling down the correction proportional to the difference of the measurement norm to the "assumed" 9.81m/s² (acceleration due to gravity).

If you have clean measurements this works really well. But if you have vibrations, using the gravity heuristic to reduce the accel correction might be counter productive since the norm of the measurement might always be way off compared to the 9.81m/s² even if you are still on ground.
So I would recommend to test this on the bench/ground first. Just increase throttle and watch either the accel measurements directly or look at the resulting "weight" in the AHRS_QUAT_INT message. It should stay close to 1 (no reduction) and go down significantly. A (continuous) acceleration though should lower the weight.
If the vibration turns out to be problem in your case, add the ahrs_int_cmpl_quat settings file and reduce the gravity_heuristic_factor to e.g. 10 and check what difference it makes.

If you have a lot of vibrations, you can try to increase the FIR_FILTER_SIZE in ahrs_int_cmpl_quat.c Line 281. This is a really simple FIR lowpass filter on the accel measurements used for the gravity heuristic.

Use GPS course or magnetometer to estimate heading?
Again there is no easy answer to this... strongly depends on what kind of airframe (and in which weather conditions) you fly.

As a rule of thumb, heading estimation via GPS course usually works well for stable airframes flown at a steady speed with little side slip and in nice weather. If you start getting significant side slip or the airframe is _very_ agile, it might be a bit problematic. Also ground speed dropping close to zero (e.g. against strong wind) becomes a problem.

Using a magnetometer does not have the above problems. BUT it needs to be calibrated and ideally this would be constant (i.e. no induced magnetic fields due to motor current, etc.). Also see ImuCalibration: Calibrating_for_Current on that point.


Lastly you can also adjust the "cut-off" frequency (AHRS_[ACCEL|MAG]_OMEGA) and damping (AHRS_[ACCEL|MAG]_ZETA) for the accel and mag updates separately.
This can also be done via settings while running...

Cheers, Felix

On Fri, Oct 18, 2013 at 9:51 AM, Prof. Dr.-Ing. Heinrich Warmers <address@hidden> wrote:
Hello,
nice work.
In the mikrokopter forum they take a temperature flow  accelerometer  with a bandwidth of only 17Hz.
This sensor cost only $4 and may be a solution for many problems.


Heinrich

Stephen Dwyer schrieb:

Hello,

Check this page, and update as necessary, as well:

Hopefully that helps a bit. As mentioned, managing the damping characteristics and natural frequency of your mount is critical.

Thanks,
-Stephen Dwyer


On Thu, Oct 17, 2013 at 11:37 AM, Jorge Pantoja <address@hidden> wrote:
Hello,


Thank you for your explanation. I will make my IMU heavier and let you know how my flights go this weekend.


Best Regards,
Jorge 

On 17/10/2013, at 12:29, Christophe De Wagter <address@hidden> wrote:

In vibration theory you have

M mass: f = m xdoubledot
K spring: f = x k
C real damper: f= c xdot

Perturbation F1

Goal:

Using "vibration damping material" (e.g. foam = spring with damping) you want to reduce the high frequency disturbance (prop) while still showing the low frequency signal (flight).

Choose M/k ( or eigenfrequency) properly

E.g.1 aspirin 8 gr (small m) on full sponge (big k): will only form a low pass for very high frequencies e.g. 200 hz: will not dampen your motor vibrations of 8000 rpm (note that it will help very significantly in the case of hard impact though)

E.g.2 aspirin on large battery (large m) on 4 small corners of foam (small k). Filters much much more vibrations including lower frequencies and should in most cases significantly reduce motor vibration measurement.

Helicopters typically put their whole avionics plus battery in a 4 small damper mounted box to handle the huge and relatively slow freq main rotor vibration.

PS: once the vibration is mechanically well within the measurement range, software filtering could also be applied.

On Oct 17, 2013 2:05 PM, "Reto Büttner" <address@hidden> wrote:
Did you make the IMU heavy or locate the IMU on the batteries? To our experience that is essential. Foam alone with no additional inertia on the IMU will likely not help.
 
Regards, Reto
 


2013/10/17 GalapagosUAV <address@hidden>
Hello,


I am also experimenting some interference due to my aircraft's engine vibration. The IMU I am using is the CHIMU. How can I integrate a way to filter this vibrations? I have my CHIMU mounted on a soft adhesive sponge and my propeller is well balanced to isolate as many vibrations as I can.

Thanks for your help.

Best Regards,
Jorge

Sent from my iPad

On 16/10/2013, at 12:13, "Prof. Dr.-Ing. Heinrich Warmers" <address@hidden> wrote:

Hi,
The DCM is affected by vibrations.
Also the DCM needs  zero rate sensors values  +-(0.0 ..0.5°/S) and make the accelerations values correct  (x=0 y=0 z=-9.81m/s*s).
Mount the IMU  exact.
Make the IMU heavy or locate the IMU on the batteries.
Balance the propeller well.

Heinrich


Refik Sever schrieb:

Hello,

 

We have been using ahrs_float_dcm in our fixedwing airframe file. We have been experiencing problems due to vibrations in our last 10-15 flights. Although we tried to decrease the vibrations, the attitude drifts after some seconds.

 

There is not enough documentation about ahrs subsystem in the wiki. I don't know the main differences between ahrs_int_cmpl_quat and ahrs_float_dcm. In what conditions do we select each of them? Since we have a lot vibrations, do you recommend to use ahrs_int_cmpl_quat instead of float_dcm? 

 

Could somebody write a brief explanation about selection criteria? When to use each of them? When to use GPS_heading or magnetometer heading?

 

Our airplane is slow, sometimes our ground speed decreases too much (it can be also negative). DO you recommend to use GPS heading in this case?

 

Regards,

Refik  

 

From: address@hidden [mailto:address@hidden] On Behalf Of Felix Ruess
Sent: Friday, October 11, 2013 5:08 PM
To: Paparazzi devel list
Subject: [Paparazzi-devel] significant improvements merged to master

 

Hi all,

 

just merged three larger pull requests with significant improvements to master:

 

Proper scaling of corrections.

Using AHRS_PROPAGATE_FREQUENCY, AHRS_CORRECT_FREQUENCY and AHRS_MAG_CORRECT_FREQUENCY.

Hence this will also give you correct gains for 100Hz fixedwings, see #240.

    

Allow tuning of the accel and mag correction natural freqency and damping.

Tunable gravity_heuristic_factor (set to zero to turn it off and replaces the boolean AHRS_GRAVITY_UPDATE_NORM_HEURISTIC)

If you have high vibrations, reduce this factor or completely turn it off...

 

 

Main benefits:

Less crappy handler functions in main.c files

Possibility to use multiple sources of sensors (integrated to the board or not)

The filters don't need to know who is sending the raw values (not completely true with the old alt_float filter yet)

    

The pressure are now standardized in Pascal and the standard atmosphere model is used

    

The INS_BARO_SENS is hence not needed anymore.

Onboard baros are automatically available in fixedwing firmware as well (use same code as rotorcraft now).

    

Disable onboard baro with <configure name="USE_BARO_BOARD" value="FALSE"/>

Also all baro_board implementations use the same BARO_BOARD_SENDER_ID,

since there can only be one baro_board at the same time and this provides a good default for INS_BARO_ID.

So if you want to use an onboard baro the INS_BARO_ID is already ok (also if you have additional baro modules).

To use a baro module for INS: <define name="INS_BARO_ID" value="BARO_x_SENDER_ID"/>

 

Some stuff to check before using: check conversion factor to convert ADC values to Pascal

(mostly older boards/baro, recent digital sensors can output pressure in Pascal already)

 

 

Now horizontal guidance returns commands in north/east earth frame and doesn't already rotate it to body frame.

This allows for better handling of them in different controllers.

    

New and properly working transformations from earth commands to quaternions added.

No proper fixedpoint implementation so far... no change there compared to current master though. Should still be done for efficiency at some point.

    

IMPORTANT: This does NOT have the feature to "add" roll/pitch setpoints via RC in nav/hover anymore.

Instead you can give velocity commands in hover mode via RC.

    

Includes max bank improvements proposed in #546:

    

Split PD and I-gain with separate max bank

- no wind: integrator (trim attitude) = 0, PD maxbank = -20 to 20 extra: total: -20 to 20

- huge wind: integrator (trim attitude) = 20, PD maxbank = -20 to 20 extra: total: 0 to 40

Put gain before integrator to get better insight in the saturation values

Reduce integration overshoots while increasing integration speed by adding the speed error as well.

- no speed error: integrate as before

- counterproductive speed error, integrate faster

If the position error is already decreasing fast, no integrator is needed or it will overshoot.

 

 

Cheers, Felix


_______________________________________________ Paparazzi-devel mailing list address@hidden https://lists.nongnu.org/mailman/listinfo/paparazzi-devel
_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________ Paparazzi-devel mailing list address@hidden https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



--
Jorge Pantoja
Program Manager/Liaison
 

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



reply via email to

[Prev in Thread] Current Thread [Next in Thread]