Difference between revisions of "Sensors/Airspeed"

From PaparazziUAV
Jump to navigation Jump to search
m
 
(22 intermediate revisions by 7 users not shown)
Line 3: Line 3:
By default, in the airborne code, airspeed is estimated by measuring the GPS ground speed. The related control loops are described [[Control_Loops|here]]. This gives reasonable results particularly in calm weather conditions. Adding an airspeed sensor measures actual airspeed resulting in better throttle control and aircraft performance especially in windy conditions. It is possible to build your own airspeed sensor by using pressure sensors. To start with adding airspeed sensors it is easier to buy pre-build calibrated airspeeds sensors. This page is currently mainly about how to do just that.
By default, in the airborne code, airspeed is estimated by measuring the GPS ground speed. The related control loops are described [[Control_Loops|here]]. This gives reasonable results particularly in calm weather conditions. Adding an airspeed sensor measures actual airspeed resulting in better throttle control and aircraft performance especially in windy conditions. It is possible to build your own airspeed sensor by using pressure sensors. To start with adding airspeed sensors it is easier to buy pre-build calibrated airspeeds sensors. This page is currently mainly about how to do just that.


== Connecting an EagleTree Airspeed Sensor ==
== How does it work internally ==
 
The altitude and airspeed loops are separated as shown in the diagram below. Basically the throttle and pitch are controlled independently and are not coupled in the control loops. Of course one affects the other but the control loops are independent. Please see the [[Control_Loops#Control_loops_using_Airspeed_Sensor|control loops]] for a more detailed block diagram. The airspeed is controlled by two cascaded Proportional–Integral (PI) loops. The first loop is used to regulate the ground speed and the second the airspeed. This is done just to ensure that if the ground speed drops below a certain value the airspeed will be increased to compensate in order to maintain a valid GPS heading. If you happen to have a 3axis magnetometer build in your airframe for getting the heading values, maintaining a certain GPS speed for getting a heading is not needed.
 
[[Image:Airspeed.png|left|800px]]
<br style="clear:both">
The following plot is from an actual test flight after spending some time setting the loop gains  Here the possibility to perform real-time tuning through the GCS is a real time saver. In the test, the an airplane was flying circles at a constant altitude, except in the end of the flight. The wind was about 5 m/s, judging from the ground speed variations. In the middle there is an example of what happens when the ground speed falls below the setpoint. Finally the altitude setpoint was changed to verify that the airspeed will be maintained while climbing.
[[Image:PlotAS2.png|left|600px]]
<br style="clear:both">
The benefits of the airspeed hold are obvious in this example. The throttle adjusts to keep the airspeed close to the setpoint.
[[Image:09_10_04__17_50_27_as1.png|left|600px]]
<br style="clear:both">
 
== Measuring ==


The [http://www.eagletreesystems.com/Standalone/standalone.htm EagleTree Airspeed Sensor] is a low cost module and comes with a very good pitot tube (Prandtl style, pitot-static tube) that includes static and dynamic ports. It has an [http://en.wikipedia.org/wiki/I²C I²C] interface that connects directly to the Autopilot I²C port. The paparazzi autopilot code is able to regulate the throttle in order to keep the airspeed constant (and a minimum ground speed).  
Sometimes it is very helpful for tuning your aircraft that you only measure the airspeed without controlling you aircraft behavior. This can be accomplished in the following way:
Replace the '''USE_AIRSPEED''' define with '''MEASURE_AIRSPEED'''.
If you want to get sensor information as it is acquired without delay through the PERIODIC_SEND_ telemetry mechanism, please set '''SENSOR_SYNC_SEND''' instead. Note that defining MEASURE_AIRSPEED and not USE_AIRSPEED results in the normal AIRSPEED message containing rather useless information (it is simply four copies of estimator_airspeed, which is not updated by the airspeed sensor, though appears to be updated a very low rate '''FIX THIS?'''). Since the airspeed control loops are not active, one can vary the frequency of the raw measurements by adjusting the rate at which the airspeed_ets module is called in conf/modules/airspeed_ets.xml in the periodic function frequency.
 
= Airspeed sensors =
 
== EagleTree Airspeed Sensor ==
 
=== Connecting an EagleTree Airspeed Sensor ===
 
The [http://www.eagletreesystems.com/Standalone/standalone.htm EagleTree Airspeed Sensor] is a low cost module and comes with a very good pitot tube (Prandtl style, pitot-static tube) that includes static and dynamic ports, it's resolution is 0.45 m/s and it's max speed is 156 m/s. It has an [http://en.wikipedia.org/wiki/I²C I²C] interface that connects directly to the Autopilot I²C port. The paparazzi autopilot code is able to regulate the throttle in order to keep the airspeed constant (and a minimum ground speed).  


When you buy the airspeed sensor it is set to operate in the default mode. Make sure you did not set it somehow to 3rd party mode.
When you buy the airspeed sensor it is set to operate in the default mode. Make sure you did not set it somehow to 3rd party mode.
Line 16: Line 40:
  Brown wire: SCL
  Brown wire: SCL


== Making hardware known to the Autopilot ==
'''See the [[Module/Airspeed_ETS|airspeed_ets module]] page for configuration.'''
To get it all to work the hardware must be made know to the autopilot code. See the easystar_ets_example.xml airframe as an example.
 
=== EagleTree sensor in 3rd party mode ===
 
While it is possible to use the sensors in a mode where values are the real values measured a.k.a. 3rd party mode, for regular use with the autopilot it has no specific advantage. Since the paparazzi already contain code to convert values to real speed values. Using the default setting is even a simpler if you have an eagletree logger and inbetween do some measurement with it, you do not need to reprogram the sensors if you connect them to the Autopilot board again.  
 
==== Direct mode ====


Just add the module to the fixedwing firmware in your airframe file:
Optionally if you have a special requirement and want to use the ''direct mode'', it is possible. For this at the moment one needs to use the Eagletree software under Windows. [[Image:SetSensorFor3rPartyModeRealValues.jpg|240px]]
  <modules>
 
    <load name="airspeed_ets.xml"/>
This software runs fine under Linux Wine. The application is using the USB port in HID mode. Make sure your run  Wine 2.0 or higher.
  </modules>
and add the aggressive climb flag, define which I2C device you are enabling and enable airspeed control:
  <target name="ap" board="twog_1.0">
      <define name="AGR_CLIMB"/>
      <define name="USE_I2C0"/>
      <define name="USE_AIRSPEED"/>
  </target>


You can also set some '''optional parameters to change the default configuration'''. For example to use i2c1 instead of i2c0, a scale of 2 (default is 1.8) and offset of 50 (default is 0):
== Sensortechnics Airspeed Sensor ==
  <modules>
    <load name="airspeed_ets.xml">
      <define name="AIRSPEED_ETS_SCALE"  value="2"/>
      <define name="AIRSPEED_ETS_OFFSET"  value="50"/>
      <define name="AIRSPEED_ETS_I2C_DEV" value="i2c1"/>
    </load>
  </modules>


== Airframe configuration ==
[http://www.sensortechnics.com Sensortechnics] provides a lot of solution for pressure measurements, absolute or differential, using analog or digital (i2c) outputs.
Now to use real airspeed values for adjusting your aircraft autopilot behavior, add the following to the end of the "VERTICAL CONTROL" section of your airframe file:


    <!-- auto airspeed and altitude inner loop (for airspeed sensor) -->
For airspeed measurements on low speed MAVs, a good choice is the [http://www.sensortechnics.com/en/products/pressure-sensors-and-transmitters/amplified-pressure-sensors/lba/ LBA series], especially the [http://www.sensortechnics.com/cms/upload/appnotes/AN_LBA_E_11162.pdf LBAS500UF6S].
    <define name="AUTO_AIRSPEED_SETPOINT" value="13.0" unit="m/s"/>
    <define name="AUTO_AIRSPEED_PGAIN" value="0.060"/>
    <define name="AUTO_AIRSPEED_IGAIN" value="0.050"/>
 
    <define name="AUTO_GROUNDSPEED_SETPOINT" value="7.0" unit="m/s"/>
    <define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
    <define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/> 
 
Note that the SETPOINT values may need to be adjusted to suit your aircraft.


Note that depending on whether you set the AIRSPEED setpoint or the GROUNDSPEED setpoint higher, either constant airspeed or constant groundspeed, respectively, will be the goal of the controller.
This sensor can be used with the generic [http://docs.paparazziuav.org/latest/module__airspeed_adc.html '''airspeed_adc''' module]. Note that it may be necessary to use a divisor bridge to adapt the 5V output of the sensor to the 3.3V ADC input of the autopilot.


See paparazzi/conf/airframes/easystar_ets_example.xml for an example airframe configuration.
== MS45xx ==


== Seeing the speed values ==
[[Image:MS4525DO.jpg|200px]]
To debug or log the raw values from the ETS airspeed sensor define SENSOR_SYNC_SEND in your airframe file to send the message AIRSPEED_ETS on every sensor reading. Note that defining this sends the AIRSPEED_ETS message at the sensor read rate as defined in conf/modules/airspeed_ets.xml. This does not have any bearing on the AIRSPEED message (if both SENSOR_SYNC_SEND and USE_AIRSPEED are defined, then both messages are sent).
  <modules>
    <load name="airspeed_ets.xml">
      <define name="SENSOR_SYNC_SEND"/>
    </load>
  </modules>


A MS4525DO based sensor user could benefit from built-in temperature compensation.


The general airspeed can be displayed in the Messages tool by adding the AIRSPEED message to /conf/telemetry/default.xml as follows:
Application notes to accompany this product:
  <process name="Ap">
    <mode name="default">
# [http://www.meas-spec.com/downloads/MS45xx_Series_Application_Note.pdf MS45xx Series Application Notes]
      <message name="AIRSPEED"  period="1.0"/>
# [http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf Interfacing to MEAS Digital Pressure Modules]
      ...
# [http://www.meas-spec.com/downloads/Configuration,_POR_and_Power_Consumption.pdf Configuration, POR and Power Consumption.]


The AIRSPEED_ETS message does NOT need to be added to the telemetry configuration since it is sent directly by the module if SENSOR_SYNC_SEND is defined.
[http://www.digikey.com/catalog/en/partgroup/ms4525do/29060 One can buy one here at digikey]


NOTES
To use MS4525 you can load the [http://docs.paparazziuav.org/latest/module__airspeed_ms45xx_i2c.html airspeed_ms45xx_i2c.xml module], e.g. put these lines in the modules section of your airframe file:
# In the GCS, the strip displays ground speed and **not** airspeed by default. In order to display airspeed, drag-and-drop the airspeed message field from the Messages tool onto the 2D map of the GCS.  
{{Box Code|conf/airframes/myplane.xml|
# The telemetry name AIRSPEEDshould actually be called SPEED and contains Groundspeed and airspeed return values.
<source lang="xml">
  <modules>
    <load name="airspeed_ms45xx_i2c.xml">
      <define name="MS45XX_I2C_DEV" value="i2c1"/>
      <define name="MS45XX_PRESSURE_RANGE" value="1"/>
      <define name="MS45XX_OUTPUT_TYPE" value="0"/>
      <define name="MS45XX_PRESSURE_OFFSET" value="8549.0"/> <!-- 8542.0-->
    </load>
  </modules>
</source>
}}


== How does it work internally ==
== Duo MS5611 ==


The altitude and airspeed loops are separated as shown in the diagram below. Basically the throttle and pitch are controlled independently and are not coupled in the control loops. Of course one affects the other but the control loops are independent. Please see the [[Control_Loops#Control_loops_using_Airspeed_Sensor|control loops]] for a more detailed block diagram. The airspeed is controlled by two cascaded Proportional–Integral (PI) loops. The first loop is used to regulate the ground speed and the second the airspeed. This is done just to ensure that if the ground speed drops below a certain value the airspeed will be increased to compensate in order to maintain a valid GPS heading. If you happen to have a 3axis magnetometer build in your airframe for getting the heading values, maintaining a certain GPS speed for getting a heading is not needed.
Two MS5611 working in cooperation. see http://blueflyvario.blogspot.de/2013/06/air-speed-from-two-ms5611.html


[[Image:Airspeed.png|left|800px]]
== [[Sensors/AMSYS|AMS 5812-0003 / AMS 5812-0001]]==
<br style="clear:both">
The following plot is from an actual test flight after spending some time setting the loop gains  Here the possibility to perform real-time tuning through the GCS is a real time saver. In thi test, the an airplane was flying circles at a constant altitude, except in the end of the flight. The wind was about 5 m/s, judging from the ground speed variations. In the middle there is an example of what happens when the ground speed falls below the setpoint. Finally the altitude setpoint was changed to verify that the airspeed will be maintained while climbing.
[[Image:PlotAS2.png|left|600px]]
<br style="clear:both">
The benefits of the airspeed hold are obvious in this example. The throttle adjusts to keep the airspeed close to the setpoint.
[[Image:09_10_04__17_50_27_as1.png|left|600px]]
<br style="clear:both">


== Measuring ==
[http://www.amsys.info/drucksensor/differenzdrucksensor.htm EU distributor]
[http://www.servoflo.com/product-guide-downloads/low-pressure-guide/download/398/847/17.html US Distributor]


Sometimes it is very helpful for tuning your aircraft that you only measure the airspeed without controlling you aircraft behavior. This can be accomplished in the following way:
Comes as sensor only and has a digital I2C and an analog 0.5 V - 4.5 V interface. At least two pull-up resistors (4.7 kOhm) and the wiring have to be added for I2C use. This can be done directly on the sensor and does not necessarily have to be on a special pcb.
Replace the '''USE_AIRSPEED''' define with '''MEASURE_AIRSPEED'''.
If you want to get sensor information as it is acquired without delay through the PERIODIC_SEND_ telemetry mechanism, please set '''SENSOR_SYNC_SEND''' instead. Note that defining MEASURE_AIRSPEED and not USE_AIRSPEED results in the normal AIRSPEED message containing rather useless information (it is simply four copies of estimator_airspeed, which is not updated by the airspeed sensor, though appears to be updated a very low rate '''FIX THIS?'''). Since the airspeed control loops are not active, one can vary the frequency of the raw measurements by adjusting the rate at which the airspeed_ets module is called in conf/modules/airspeed_ets.xml in the periodic function frequency.


== EagleTree sensor in 3rd party mode ==
See [[Sensors/AMSYS|the sensor page]] for I2C addressing.


While it is possible to use the sensors in a mode where values are the real values measured a.k.a. 3rd party mode, for regular use with the autopilot it has no specific advantage. Since the paparazzi already contain code to convert values to real speed values. Using the default setting is even better if you have an eagletree logger and inbetween do some measurement with it, you do not need to reprogram the sensors if you connect them to the Autopilot board again. But maybe you have a special requirement and want to use the direct mode, it is possible. For this at the moment one needs to use the Eagletree software under Windows. [[Image:SetSensorFor3rPartyModeRealValues.jpg|240px]]
The biggest advantage of the -0001 is its resolution, at a loiter airspeed of 8.5 m/s, the resolution of the -0001 is about 0,0038 m/s whereas the resolution of the MS4525 would be 0,082 m/s (using the data provided by 3DR).
This advantage gets smaller, the faster the aircraft travels. At 25 m/s the resolution is about 0,0013 m/s and 0,028 m/s. Both resolutions should be more then enough at that speed.


Maximum speed for the -0001 is about 41 m/s (0 ... 10.34 mbar), for the -0003 about 58 m/s (0 ... 20.68 mbar).


Regardless that his software runs fine under Linux Wine, using is not possible since the USB port is used in HID mode and as of Wine v1.2 using the USB bus under wind this way is not possible yet. There is however work done and on its way that USB ports do work under Wine for HID device.
= Future =


== What needs to be improved ==
Just as with everything in the UAS world, lots of improvements are still possible.


The following aspects still need to be looked at, revert to GPS measurements only if the airspeed sensor fails. If you are able to code I would be really great if you would help out by testing and improving this part of the code.
'''What could be improved:'''


Thanks very much to [http://vrhome.net/vassilis/ Vassilis] and [http://www.openuas.org/ OpenUAS]for developing and testing the code.
# Maybe revert to GPS measurements only if the airspeed sensor fails.
# Detect Swap of static/dynamic port at pre-flight test


[[Category:Software]] [[Category:Modules]] [[Category:Sensors]] [[Category:User_Documentation]]
[[Category:Software]] [[Category:Sensors]] [[Category:User_Documentation]]

Latest revision as of 18:09, 5 August 2020

Introduction

By default, in the airborne code, airspeed is estimated by measuring the GPS ground speed. The related control loops are described here. This gives reasonable results particularly in calm weather conditions. Adding an airspeed sensor measures actual airspeed resulting in better throttle control and aircraft performance especially in windy conditions. It is possible to build your own airspeed sensor by using pressure sensors. To start with adding airspeed sensors it is easier to buy pre-build calibrated airspeeds sensors. This page is currently mainly about how to do just that.

How does it work internally

The altitude and airspeed loops are separated as shown in the diagram below. Basically the throttle and pitch are controlled independently and are not coupled in the control loops. Of course one affects the other but the control loops are independent. Please see the control loops for a more detailed block diagram. The airspeed is controlled by two cascaded Proportional–Integral (PI) loops. The first loop is used to regulate the ground speed and the second the airspeed. This is done just to ensure that if the ground speed drops below a certain value the airspeed will be increased to compensate in order to maintain a valid GPS heading. If you happen to have a 3axis magnetometer build in your airframe for getting the heading values, maintaining a certain GPS speed for getting a heading is not needed.

Airspeed.png


The following plot is from an actual test flight after spending some time setting the loop gains Here the possibility to perform real-time tuning through the GCS is a real time saver. In the test, the an airplane was flying circles at a constant altitude, except in the end of the flight. The wind was about 5 m/s, judging from the ground speed variations. In the middle there is an example of what happens when the ground speed falls below the setpoint. Finally the altitude setpoint was changed to verify that the airspeed will be maintained while climbing.

PlotAS2.png


The benefits of the airspeed hold are obvious in this example. The throttle adjusts to keep the airspeed close to the setpoint.

09 10 04 17 50 27 as1.png


Measuring

Sometimes it is very helpful for tuning your aircraft that you only measure the airspeed without controlling you aircraft behavior. This can be accomplished in the following way:

Replace the USE_AIRSPEED define with MEASURE_AIRSPEED. If you want to get sensor information as it is acquired without delay through the PERIODIC_SEND_ telemetry mechanism, please set SENSOR_SYNC_SEND instead. Note that defining MEASURE_AIRSPEED and not USE_AIRSPEED results in the normal AIRSPEED message containing rather useless information (it is simply four copies of estimator_airspeed, which is not updated by the airspeed sensor, though appears to be updated a very low rate FIX THIS?). Since the airspeed control loops are not active, one can vary the frequency of the raw measurements by adjusting the rate at which the airspeed_ets module is called in conf/modules/airspeed_ets.xml in the periodic function frequency.

Airspeed sensors

EagleTree Airspeed Sensor

Connecting an EagleTree Airspeed Sensor

The EagleTree Airspeed Sensor is a low cost module and comes with a very good pitot tube (Prandtl style, pitot-static tube) that includes static and dynamic ports, it's resolution is 0.45 m/s and it's max speed is 156 m/s. It has an I²C interface that connects directly to the Autopilot I²C port. The paparazzi autopilot code is able to regulate the throttle in order to keep the airspeed constant (and a minimum ground speed).

When you buy the airspeed sensor it is set to operate in the default mode. Make sure you did not set it somehow to 3rd party mode.

First, connect the sensor directly to the TWOG, Tiny or Lisa/M autopilot board via the I²C connector. The connector is J6 on the TWOG and Tiny and I2C on Lisa board. The wires coming from the sensor module have the following layout:

Red wire: 5V
White wire: Ground
Yellow wire: SDA
Brown wire: SCL

See the airspeed_ets module page for configuration.

EagleTree sensor in 3rd party mode

While it is possible to use the sensors in a mode where values are the real values measured a.k.a. 3rd party mode, for regular use with the autopilot it has no specific advantage. Since the paparazzi already contain code to convert values to real speed values. Using the default setting is even a simpler if you have an eagletree logger and inbetween do some measurement with it, you do not need to reprogram the sensors if you connect them to the Autopilot board again.

Direct mode

Optionally if you have a special requirement and want to use the direct mode, it is possible. For this at the moment one needs to use the Eagletree software under Windows. SetSensorFor3rPartyModeRealValues.jpg

This software runs fine under Linux Wine. The application is using the USB port in HID mode. Make sure your run Wine 2.0 or higher.

Sensortechnics Airspeed Sensor

Sensortechnics provides a lot of solution for pressure measurements, absolute or differential, using analog or digital (i2c) outputs.

For airspeed measurements on low speed MAVs, a good choice is the LBA series, especially the LBAS500UF6S.

This sensor can be used with the generic airspeed_adc module. Note that it may be necessary to use a divisor bridge to adapt the 5V output of the sensor to the 3.3V ADC input of the autopilot.

MS45xx

MS4525DO.jpg

A MS4525DO based sensor user could benefit from built-in temperature compensation.

Application notes to accompany this product:

  1. MS45xx Series Application Notes
  2. Interfacing to MEAS Digital Pressure Modules
  3. Configuration, POR and Power Consumption.

One can buy one here at digikey

To use MS4525 you can load the airspeed_ms45xx_i2c.xml module, e.g. put these lines in the modules section of your airframe file:

File: conf/airframes/myplane.xml
  <modules>
    <load name="airspeed_ms45xx_i2c.xml">
      <define name="MS45XX_I2C_DEV" value="i2c1"/>
      <define name="MS45XX_PRESSURE_RANGE" value="1"/>
      <define name="MS45XX_OUTPUT_TYPE" value="0"/>
      <define name="MS45XX_PRESSURE_OFFSET" value="8549.0"/>  <!-- 8542.0-->
    </load>
  </modules>

Duo MS5611

Two MS5611 working in cooperation. see http://blueflyvario.blogspot.de/2013/06/air-speed-from-two-ms5611.html

AMS 5812-0003 / AMS 5812-0001

EU distributor US Distributor

Comes as sensor only and has a digital I2C and an analog 0.5 V - 4.5 V interface. At least two pull-up resistors (4.7 kOhm) and the wiring have to be added for I2C use. This can be done directly on the sensor and does not necessarily have to be on a special pcb.

See the sensor page for I2C addressing.

The biggest advantage of the -0001 is its resolution, at a loiter airspeed of 8.5 m/s, the resolution of the -0001 is about 0,0038 m/s whereas the resolution of the MS4525 would be 0,082 m/s (using the data provided by 3DR). This advantage gets smaller, the faster the aircraft travels. At 25 m/s the resolution is about 0,0013 m/s and 0,028 m/s. Both resolutions should be more then enough at that speed.

Maximum speed for the -0001 is about 41 m/s (0 ... 10.34 mbar), for the -0003 about 58 m/s (0 ... 20.68 mbar).

Future

Just as with everything in the UAS world, lots of improvements are still possible.

What could be improved:

  1. Maybe revert to GPS measurements only if the airspeed sensor fails.
  2. Detect Swap of static/dynamic port at pre-flight test