paparazzi-commits
[Top][All Lists]
Advanced

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

[paparazzi-commits] [4232] Support for the EagleTree airspeed and altime


From: Vassilis V.
Subject: [paparazzi-commits] [4232] Support for the EagleTree airspeed and altimeter I2C sensors ( V3 hardware).
Date: Tue, 06 Oct 2009 02:47:21 +0000

Revision: 4232
          http://svn.sv.gnu.org/viewvc/?view=rev&root=paparazzi&revision=4232
Author:   vassilis
Date:     2009-10-06 02:47:20 +0000 (Tue, 06 Oct 2009)
Log Message:
-----------
Support for the EagleTree airspeed and altimeter I2C sensors (V3 hardware).
Vertical control loops have been updated to make use of the new measurements.
See conf/airframes/easystar2.xml for an example configuration.

Modified Paths:
--------------
    paparazzi3/trunk/conf/messages.xml
    paparazzi3/trunk/sw/airborne/airspeed.c
    paparazzi3/trunk/sw/airborne/ap_downlink.h
    paparazzi3/trunk/sw/airborne/estimator.c
    paparazzi3/trunk/sw/airborne/estimator.h
    paparazzi3/trunk/sw/airborne/fw_v_ctl.c
    paparazzi3/trunk/sw/airborne/fw_v_ctl.h
    paparazzi3/trunk/sw/airborne/main_ap.c

Added Paths:
-----------
    paparazzi3/trunk/conf/airframes/easystar2.xml
    paparazzi3/trunk/sw/airborne/airspeed_ets.c
    paparazzi3/trunk/sw/airborne/airspeed_ets.h
    paparazzi3/trunk/sw/airborne/baro_ets.c
    paparazzi3/trunk/sw/airborne/baro_ets.h

Added: paparazzi3/trunk/conf/airframes/easystar2.xml
===================================================================
--- paparazzi3/trunk/conf/airframes/easystar2.xml                               
(rev 0)
+++ paparazzi3/trunk/conf/airframes/easystar2.xml       2009-10-06 02:47:20 UTC 
(rev 4232)
@@ -0,0 +1,241 @@
+<!DOCTYPE airframe SYSTEM "airframe.dtd">
+
+<!-- 
+       Multiplex EasyStar, using rudder
+       TWOG v1 board
+       Tilted infrared sensor
+       XBee 2.4GHz modem in transparent mode           
+-->
+
+<airframe name="EasyStar2 - TWOG v1">
+
+  <modules>
+    <load name="campod.xml"/>
+  </modules>
+
+<!-- commands section -->
+  <servos>
+    <servo name="THROTTLE"      no="0" min="1120" neutral="1120" max="1920"/>  
+    <servo name="ELEVATOR"      no="6" min="1100" neutral="1514" max="1900"/>
+    <servo name="RUDDER"        no="7" min="2050" neutral="1612" max="950"/>
+    <servo name="CAM_PAN"       no="3" min="1000" neutral="1500" max="2000"/>
+    <servo name="CAM_TILT"      no="4" min="1000" neutral="1450" max="2000"/>
+  </servos>
+  
+  <commands>
+    <axis name="THROTTLE" failsafe_value="0"/>  
+    <axis name="ROLL"     failsafe_value="0"/>
+    <axis name="PITCH"    failsafe_value="0"/>  
+    <axis name="CAM_PAN"  failsafe_value="0"/>
+    <axis name="CAM_TILT"  failsafe_value="0"/>
+  </commands>
+
+  <rc_commands>
+    <set command="ROLL"      value="@ROLL"/>
+    <set command="PITCH"     value="@PITCH"/>
+    <set command="THROTTLE"  value="@THROTTLE"/> 
+    <set command="CAM_PAN"   value="@CAM_PAN"/>
+    <set command="CAM_TILT"   value="@CAM_TILT"/>
+  </rc_commands> 
+
+  <command_laws>
+    <set servo="THROTTLE"    value="@THROTTLE"/>
+    <set servo="RUDDER"      value="@ROLL"/>  
+    <set servo="ELEVATOR"    value="@PITCH"/>      
+    <set servo="CAM_PAN"     value="@CAM_PAN"/>   
+    <set servo="CAM_TILT"     value="@CAM_TILT"/>
+  </command_laws>
+
+  <section name="AUTO1" prefix="AUTO1_">
+    <define name="MAX_ROLL" value="RadOfDeg(50)"/>
+    <define name="MAX_PITCH" value="RadOfDeg(40)"/>
+  </section>
+
+  <section name="adc" prefix="ADC_CHANNEL_">
+    <define name="IR1" value="ADC_1"/>
+    <define name="IR2" value="ADC_2"/>
+    <define name="IR_TOP" value="ADC_0"/>
+    <define name="IR_NB_SAMPLES" value="16"/>
+  </section>
+
+  <section name="INFRARED" prefix="IR_">
+    <define name="ADC_IR1_NEUTRAL" value="512"/>
+    <define name="ADC_IR2_NEUTRAL" value="510"/>
+    <define name="ADC_TOP_NEUTRAL" value="516"/>
+
+    <define name="LATERAL_CORRECTION" value="0.7"/>
+    <define name="LONGITUDINAL_CORRECTION" value="0.7"/>
+    <define name="VERTICAL_CORRECTION" value="1."/>
+
+    <define name="HORIZ_SENSOR_TILTED" value="1"/>
+    <define name="IR1_SIGN" value="1"/>
+    <define name="IR2_SIGN" value="-1"/>
+    <define name="TOP_SIGN" value="1"/>
+
+    <define name="ROLL_NEUTRAL_DEFAULT" value="-5.3" unit="deg"/>
+    <define name="PITCH_NEUTRAL_DEFAULT" value="-3" unit="deg"/>
+
+    <define name="CORRECTION_UP" value="1."/>
+    <define name="CORRECTION_DOWN" value="1."/>
+    <define name="CORRECTION_LEFT" value="1."/>
+    <define name="CORRECTION_RIGHT" value="1."/>
+  </section>
+
+  <section name="BAT">
+    <define name="MILLIAMP_AT_FULL_THROTTLE" value="20000" unit="mA"/>
+    <define name="CATASTROPHIC_BAT_LEVEL" value="7.5" unit="V"/>
+    <define name="CRITIC_BAT_LEVEL" value="8.5" unit="V"/>
+    <define name="LOW_BAT_LEVEL" value="9.5" unit="V"/>
+    <define name="MAX_BAT_LEVEL" value="12.5" unit="V"/>
+  </section>
+
+  <section name="MISC">
+    <define name="NOMINAL_AIRSPEED" value="15." unit="m/s"/>
+    <define name="CARROT" value="3." unit="s"/>
+    <define name="KILL_MODE_DISTANCE" value="(1.5*MAX_DIST_FROM_HOME)"/>
+    <define name="CONTROL_RATE" value="60" unit="Hz"/>
+    <define name="NO_XBEE_API_INIT" value="TRUE"/> 
+    <define name="ALT_KALMAN_ENABLED" value="TRUE"/>
+    <define name="TRIGGER_DELAY" value="1."/>
+    <define name="DEFAULT_CIRCLE_RADIUS" value="90."/>
+    <define name="MIN_CIRCLE_RADIUS" value="60."/>
+  </section>
+ 
+  <section name="VERTICAL CONTROL" prefix="V_CTL_">
+    <define name="POWER_CTL_BAT_NOMINAL" value="11.0" unit="volt"/>
+    <!-- outer loop -->
+    <define name="ALTITUDE_PGAIN" value="-0.075" unit="(m/s)/m"/>
+    <define name="ALTITUDE_MAX_CLIMB" value="4." unit="m/s"/>
+    <!-- auto throttle inner loop -->
+    <define name="AUTO_THROTTLE_NOMINAL_CRUISE_THROTTLE" value="0.5" unit="%"/>
+    <define name="AUTO_THROTTLE_MIN_CRUISE_THROTTLE" value="0.4" unit="%"/>
+    <define name="AUTO_THROTTLE_MAX_CRUISE_THROTTLE" value="0.8" unit="%"/>
+    <define name="AUTO_THROTTLE_LOITER_TRIM" value="1500" unit="pprz_t"/>
+    <define name="AUTO_THROTTLE_DASH_TRIM" value="-1000" unit="pprz_t"/>
+    <define name="AUTO_THROTTLE_CLIMB_THROTTLE_INCREMENT" value="0.1" 
unit="%/(m/s)"/>
+    <define name="AUTO_THROTTLE_PGAIN" value="-0.02" unit="%/(m/s)"/>
+    <define name="AUTO_THROTTLE_IGAIN" value="0.1"/>
+    <define name="AUTO_THROTTLE_PITCH_OF_VZ_PGAIN" value="0.05" 
unit="rad/(m/s)"/>
+    <!-- auto airspeed and altitude inner loop -->
+    <define name="AUTO_AIRSPEED_SETPOINT" value="17.5" 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="5" unit="m/s"/>
+    <define name="AUTO_GROUNDSPEED_PGAIN" value="0.75"/>
+    <define name="AUTO_GROUNDSPEED_IGAIN" value="0.25"/>     
+    <define name="AUTO_PITCH_PGAIN" value="-0.182"/>
+    <define name="AUTO_PITCH_IGAIN" value="0.010"/>
+    <define name="AUTO_PITCH_MAX_PITCH" value="RadOfDeg(25)"/>
+    <define name="AUTO_PITCH_MIN_PITCH" value="RadOfDeg(-25)"/>
+    <define name="THROTTLE_SLEW" value="1.0"/>
+  </section>
+
+  <section name="HORIZONTAL CONTROL" prefix="H_CTL_">
+    <define name="COURSE_PGAIN" value="-0.7"/>
+    <define name="ROLL_MAX_SETPOINT" value="RadOfDeg(35)" unit="radians"/>
+    <define name="PITCH_MAX_SETPOINT" value="RadOfDeg(25)" unit="radians"/>
+    <define name="PITCH_MIN_SETPOINT" value="RadOfDeg(-25)" unit="radians"/>
+    <define name="PITCH_PGAIN" value="-20000."/>
+    <define name="PITCH_DGAIN" value="1.5"/>
+    <define name="ELEVATOR_OF_ROLL" value="2500"/>
+    <define name="ROLL_ATTITUDE_GAIN" value="-7400"/>
+    <define name="ROLL_RATE_GAIN" value="-200"/>
+  </section>
+
+  <section name="NAV">
+    <define name="NAV_PITCH" value="0."/>
+    <define name="NAV_GLIDE_PITCH_TRIM" value="0"/>
+  </section>
+
+  <section name="AGGRESSIVE" prefix="AGR_">
+    <define name="BLEND_START" value="20"/><!-- Altitude Error to Initiate 
Aggressive Climb CANNOT BE ZERO!!-->
+    <define name="BLEND_END" value="8"/><!-- Altitude Error to Blend 
Aggressive to Regular Climb Modes  CANNOT BE ZERO!!-->
+    <define name="CLIMB_THROTTLE" value="0.70"/><!-- Gaz for Aggressive Climb 
-->
+    <define name="CLIMB_PITCH" value="RadOfDeg(18)"/><!-- Pitch for Aggressive 
Climb -->
+    <define name="DESCENT_THROTTLE" value="0.1"/><!-- Gaz for Aggressive 
Decent -->
+    <define name="DESCENT_PITCH" value="RadOfDeg(-20)"/><!-- Pitch for 
Aggressive Decent -->
+    <define name="CLIMB_NAV_RATIO" value="0.8"/><!-- Percent Navigation for 
Altitude Error Equal to Start Altitude -->
+    <define name="DESCENT_NAV_RATIO" value="1.0"/>
+  </section>
+
+  <section name="FAILSAFE" prefix="FAILSAFE_">
+    <define name="DELAY_WITHOUT_GPS" value="3" unit="s"/>
+    <define name="DEFAULT_THROTTLE" value="0.4" unit="%"/>
+    <define name="DEFAULT_ROLL" value="RadOfDeg(20)" unit="rad"/>
+    <define name="DEFAULT_PITCH" value="RadOfDeg(0)" unit="rad"/>
+    <define name="HOME_RADIUS" value="90" unit="m"/>
+  </section>
+  
+  <section name="DATALINK" prefix="DATALINK_">
+    <define name="DEVICE_TYPE" value="PPRZ"/>
+    <define name="DEVICE_ADDRESS" value="...."/>
+  </section>  
+
+  <section name="SIMU">
+    <define name="YAW_RESPONSE_FACTOR" value="0.5"/>
+  </section>
+
+  <makefile>
+CONFIG = \"tiny_2_1_1.h\"
+
+# Target configuration
+include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile
+
+FLASH_MODE=IAP
+
+ap.CFLAGS +=  -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DLED -DTIME_LED=1 
-DUSE_MODULES 
+ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c 
main_ap.c main.c
+
+ap.srcs += commands.c
+
+# Servo driver
+ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017
+ap.srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c
+
+# Radio configuration
+ap.CFLAGS += -DRADIO_CONTROL
+ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c  
+
+# Telemetry configuration
+ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport 
-DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 
-DDATALINK=PPRZ -DUART1_BAUD=B57600
+ap.srcs += downlink.c $(SRC_ARCH)/uart_hw.c datalink.c pprz_transport.c
+
+ap.CFLAGS += -DINTER_MCU
+ap.srcs += inter_mcu.c 
+
+# ADC configuration
+ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 
+ap.srcs += $(SRC_ARCH)/adc_hw.c
+
+# GPS configuration
+ap.CFLAGS += -DGPS -DUBX -DUSE_UART0 -DGPS_LINK=Uart0 -DUART0_BAUD=B38400 
-DGPS_USE_LATLONG -DGPS_LED=2 
+ap.srcs += gps_ubx.c gps.c latlong.c
+
+ap.CFLAGS += -DINFRARED -DALT_KALMAN
+ap.srcs += infrared.c estimator.c
+
+# Control loops
+ap.CFLAGS += -DNAV -DLOITER_TRIM
+ap.srcs += nav.c fw_h_ctl.c fw_v_ctl.c 
+
+ap.srcs += nav_line.c
+ap.srcs += nav_survey_rectangle.c
+
+# Camera control
+#ap.CFLAGS += -DCAM -DMOBILE_CAM -DPOINT_CAM -DPOINT_CAM_PITCH_ROLL 
+#-DTEST_CAM
+#ap.srcs += cam.c point.c
+
+# EagleTree sensors (altimeter and airspeed)
+ap.CFLAGS += -DUSE_AIRSPEED_ETS -DUSE_AIRSPEED -DUSE_BARO_ETS -DUSE_I2C0
+ap.srcs += airspeed.c airspeed_ets.c baro_ets.c i2c.c $(SRC_ARCH)/i2c_hw.c
+
+# Config for SITL simulation
+include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile
+sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DLOITER_TRIM -DALT_KALMAN 
-DUSE_MODULES
+sim.srcs += nav_line.c nav_survey_rectangle.c 
+sim.CFLAGS += -DUSE_AIRSPEED_ETS -DUSE_AIRSPEED -DUSE_BARO_ETS -DUSE_I2C0
+sim.srcs += airspeed.c airspeed_ets.c baro_ets.c i2c.c $(SRC_ARCH)/i2c_hw.c
+
+  </makefile>
+</airframe>


Property changes on: paparazzi3/trunk/conf/airframes/easystar2.xml
___________________________________________________________________
Added: svn:executable
   + *

Modified: paparazzi3/trunk/conf/messages.xml
===================================================================
--- paparazzi3/trunk/conf/messages.xml  2009-10-05 06:56:52 UTC (rev 4231)
+++ paparazzi3/trunk/conf/messages.xml  2009-10-06 02:47:20 UTC (rev 4232)
@@ -278,7 +278,10 @@
 
   <message name="AIRSPEED" id="45">
       <field name="adc" type="uint16"/>
-      <field name="airspeed" type="float"/>
+      <field name="airspeed" type="float" unit="m/s"/>
+      <field name="airspeed_sp" type="float" unit="m/s"/>
+      <field name="airspeed_cnt" type="float" unit="m/s"/>
+      <field name="groundspeed_sp" type="float" unit="m/s"/>
   </message>
 
   <message name="BARO_WORDS" id="46">

Modified: paparazzi3/trunk/sw/airborne/airspeed.c
===================================================================
--- paparazzi3/trunk/sw/airborne/airspeed.c     2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/airspeed.c     2009-10-06 02:47:20 UTC (rev 
4232)
@@ -2,8 +2,14 @@
 #include "adc.h"
 #include "airframe.h"
 #include "estimator.h"
+#include "gps.h"
+#include "nav.h"
 #include BOARD_CONFIG
 
+#ifdef USE_AIRSPEED_ETS
+#include "airspeed_ets.h"
+#endif
+
 #ifdef USE_AIRSPEED
 uint16_t adc_airspeed_val;
 #else
@@ -14,8 +20,9 @@
 #ifndef SITL
 static struct adc_buf buf_airspeed;
 #endif
+#elif defined(USE_AIRSPEED_ETS)
 #else
-#error "You compiled the airspeed.c file but did not ADC_CHANNEL_AIRSPEED, 
which is needed in other *.c files"
+#error "You compiled the airspeed.c file but did not ADC_CHANNEL_AIRSPEED or 
USE_AIRSPEED_ETS, which is needed in other *.c files"
 #endif
 
 void airspeed_init( void ) {
@@ -26,17 +33,24 @@
 #  ifndef SITL
      adc_buf_channel(ADC_CHANNEL_AIRSPEED, &buf_airspeed, 
ADC_CHANNEL_AIRSPEED_NB_SAMPLES);
 #  endif
+#elif defined(USE_AIRSPEED_ETS)
 #else
-#  error "You defined USE_AIRSPEED but did not assign a ADC_CHANNEL_AIRSPEED"
+#  error "You defined USE_AIRSPEED but did not define ADC_CHANNEL_AIRSPEED or 
USE_AIRSPEED_ETS"
 #endif
 }
 
 void airspeed_update( void ) {
+#ifndef SITL
 #ifdef ADC_CHANNEL_AIRSPEED
-#ifndef SITL
   adc_airspeed_val = (buf_airspeed.sum / buf_airspeed.av_nb_sample) - 
AIRSPEED_ZERO;
   float airspeed = AIRSPEED_SCALE * adc_airspeed_val;
   EstimatorSetAirspeed(airspeed);
+#elif defined(USE_AIRSPEED_ETS)
+  EstimatorSetAirspeed(airspeed_ets);
+  adc_airspeed_val = airspeed_ets_raw;
 #endif
-#endif
+#else // SITL
+  EstimatorSetAirspeed(gps_gspeed / 100.0); // FIXME: should calculate 
airspeed in the simulation model, use ground speed for now
+  adc_airspeed_val = 0;
+#endif //SITL
 }

Added: paparazzi3/trunk/sw/airborne/airspeed_ets.c
===================================================================
--- paparazzi3/trunk/sw/airborne/airspeed_ets.c                         (rev 0)
+++ paparazzi3/trunk/sw/airborne/airspeed_ets.c 2009-10-06 02:47:20 UTC (rev 
4232)
@@ -0,0 +1,151 @@
+/*
+ * Driver for the EagleTree Systems Airspeed Sensor
+ * Has only been tested with V3 of the sensor hardware
+ *
+ * Notes:
+ * Connect directly to TWOG/Tiny I2C port. Multiple sensors can be chained 
together.
+ * Sensor should be in the proprietary mode (default) and not in 3rd party 
mode.
+ * Aggressive climb mode (AGR_CLIMB) has not been tested.
+ * See conf/airframes/easystar2.xml for a configuration example.
+ *
+ * Sensor module wire assignments:
+ * Red wire: 5V
+ * White wire: Ground
+ * Yellow wire: SDA
+ * Brown wire: SCL
+ *
+ * Copyright (C) 2009 Vassilis Varveropoulos
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#include "airspeed_ets.h"
+#include "i2c.h"
+#include "nav.h"
+#include <math.h>
+
+#ifdef SITL
+#include "gps.h"
+#endif
+
+#define AIRSPEED_ETS_ADDR 0xEA
+#define AIRSPEED_ETS_REG 0x07
+#define AIRSPEED_ETS_SCALE 1.8
+#define AIRSPEED_ETS_OFFSET_MAX 1750
+#define AIRSPEED_ETS_OFFSET_MIN 1550
+#define AIRSPEED_ETS_OFFSET_NBSAMPLES_INIT 40
+#define AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG 60
+#define AIRSPEED_ETS_NBSAMPLES_AVRG 10
+
+// Global variables
+uint16_t airspeed_ets_raw;
+uint16_t airspeed_ets_offset;
+bool_t airspeed_ets_valid;
+float airspeed_ets;
+int airspeed_ets_buffer_idx;
+float airspeed_ets_buffer[AIRSPEED_ETS_NBSAMPLES_AVRG];
+
+// Local variables
+volatile bool_t airspeed_ets_i2c_done;
+bool_t airspeed_ets_offset_init;
+uint32_t airspeed_ets_offset_tmp;
+uint16_t airspeed_ets_cnt;
+
+void airspeed_ets_init( void ) {
+  int n;
+  airspeed_ets_raw = 0;
+  airspeed_ets = 0.0;
+  airspeed_ets_offset = 0;
+  airspeed_ets_offset_tmp = 0;
+  airspeed_ets_i2c_done = TRUE;
+  airspeed_ets_valid = TRUE;
+  airspeed_ets_offset_init = FALSE;
+  airspeed_ets_cnt = AIRSPEED_ETS_OFFSET_NBSAMPLES_INIT + 
AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG;
+  i2c0_buf[0] = 0;
+  i2c0_buf[1] = 0;
+  airspeed_ets_buffer_idx = 0;
+  for (n=0; n < AIRSPEED_ETS_NBSAMPLES_AVRG; ++n)
+    airspeed_ets_buffer[n] = 0.0;
+}
+
+void airspeed_ets_read( void ) {
+  // Initiate next read
+  i2c0_buf[0] = 0;
+  i2c0_buf[1] = 0;
+  i2c0_receive(AIRSPEED_ETS_ADDR, 2, &airspeed_ets_i2c_done); 
+}      
+
+void airspeed_ets_periodic( void ) {
+  int n;
+  float airspeed_tmp;
+
+  // Read raw value
+  if (i2c0_status == I2C_IDLE) {
+    // Get raw airspeed from buffer
+    airspeed_ets_raw = ((uint16_t)(i2c0_buf[1]) << 8) | 
(uint16_t)(i2c0_buf[0]);
+    // Check if this is valid airspeed
+    if (airspeed_ets_raw == 0)
+      airspeed_ets_valid = FALSE;
+    else
+      airspeed_ets_valid = TRUE;
+  }
+  // Continue only if a new airspeed value was received  
+  if (airspeed_ets_valid) {  
+    // Calculate offset average if not done already
+    if (!airspeed_ets_offset_init) {
+      --airspeed_ets_cnt;
+      // Check if averaging completed
+      if (airspeed_ets_cnt == 0) {
+        // Calculate average
+        airspeed_ets_offset = (uint16_t)(airspeed_ets_offset_tmp / 
AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG);
+        // Limit offset
+        if (airspeed_ets_offset < AIRSPEED_ETS_OFFSET_MIN)
+          airspeed_ets_offset = AIRSPEED_ETS_OFFSET_MIN;
+        if (airspeed_ets_offset > AIRSPEED_ETS_OFFSET_MAX)
+          airspeed_ets_offset = AIRSPEED_ETS_OFFSET_MAX;
+        airspeed_ets_offset_init = TRUE;
+      }
+      // Check if averaging needs to continue
+      else if (airspeed_ets_cnt <= AIRSPEED_ETS_OFFSET_NBSAMPLES_AVRG)
+        airspeed_ets_offset_tmp += airspeed_ets_raw;
+    }    
+    // Convert raw to m/s
+    if (airspeed_ets_offset_init && airspeed_ets_raw > airspeed_ets_offset)
+      airspeed_tmp = AIRSPEED_ETS_SCALE * sqrt( 
(float)(airspeed_ets_raw-airspeed_ets_offset) );
+    else
+      airspeed_tmp = 0.0;
+    // Airspeed should always be positive
+    if (airspeed_tmp < 0.0)
+      airspeed_tmp = 0.0;
+    // Moving average
+    airspeed_ets_buffer[airspeed_ets_buffer_idx++] = airspeed_tmp;
+    if (airspeed_ets_buffer_idx >= AIRSPEED_ETS_NBSAMPLES_AVRG)
+      airspeed_ets_buffer_idx = 0;
+    airspeed_ets = 0.0;
+    for (n = 0; n < AIRSPEED_ETS_NBSAMPLES_AVRG; ++n)
+      airspeed_ets += airspeed_ets_buffer[n];
+    airspeed_ets = airspeed_ets / (float)AIRSPEED_ETS_NBSAMPLES_AVRG;
+  } else {
+    airspeed_ets = 0.0;
+  }
+}
+
+
+
+


Property changes on: paparazzi3/trunk/sw/airborne/airspeed_ets.c
___________________________________________________________________
Added: svn:executable
   + *

Added: paparazzi3/trunk/sw/airborne/airspeed_ets.h
===================================================================
--- paparazzi3/trunk/sw/airborne/airspeed_ets.h                         (rev 0)
+++ paparazzi3/trunk/sw/airborne/airspeed_ets.h 2009-10-06 02:47:20 UTC (rev 
4232)
@@ -0,0 +1,19 @@
+/*
+ * Driver for the EagleTree Systems Airspeed Sensor
+ */
+
+#ifndef AIRSPEED_ETS_H
+#define AIRSPEED_ETS_H
+
+#include "std.h"
+
+extern void airspeed_ets_periodic( void );
+extern void airspeed_ets_read( void );
+extern void airspeed_ets_init( void );
+
+extern uint16_t airspeed_ets_raw;
+extern uint16_t airspeed_ets_offset;
+extern bool_t airspeed_ets_valid;
+extern float airspeed_ets;
+
+#endif // AIRSPEED_ETS_H


Property changes on: paparazzi3/trunk/sw/airborne/airspeed_ets.h
___________________________________________________________________
Added: svn:executable
   + *

Modified: paparazzi3/trunk/sw/airborne/ap_downlink.h
===================================================================
--- paparazzi3/trunk/sw/airborne/ap_downlink.h  2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/ap_downlink.h  2009-10-06 02:47:20 UTC (rev 
4232)
@@ -171,7 +171,7 @@
 #endif
 
 #ifdef USE_AIRSPEED
-#define PERIODIC_SEND_AIRSPEED(_chan) DOWNLINK_SEND_AIRSPEED (_chan, 
&adc_airspeed_val,&estimator_airspeed)
+#define PERIODIC_SEND_AIRSPEED(_chan) DOWNLINK_SEND_AIRSPEED (_chan, 
&adc_airspeed_val,&estimator_airspeed,&v_ctl_auto_airspeed_setpoint,&v_ctl_auto_airspeed_controlled,&v_ctl_auto_groundspeed_setpoint)
 #else
 #define PERIODIC_SEND_AIRSPEED(_chan) {}
 #endif

Added: paparazzi3/trunk/sw/airborne/baro_ets.c
===================================================================
--- paparazzi3/trunk/sw/airborne/baro_ets.c                             (rev 0)
+++ paparazzi3/trunk/sw/airborne/baro_ets.c     2009-10-06 02:47:20 UTC (rev 
4232)
@@ -0,0 +1,144 @@
+/*
+ * Driver for the EagleTree Systems Altitude Sensor
+ * Has only been tested with V3 of the sensor hardware
+ *
+ * Notes:
+ * Connect directly to TWOG/Tiny I2C port. Multiple sensors can be chained 
together.
+ * Sensor should be in the proprietary mode (default) and not in 3rd party 
mode.
+ * Aggressive climb mode (AGR_CLIMB) has not been tested with the barometric 
altitude.
+ * Pitch gains may need to be updated.
+ * See conf/airframes/easystar2.xml for a configuration example.
+ *
+ *
+ * Sensor module wire assignments:
+ * Red wire: 5V
+ * White wire: Ground
+ * Yellow wire: SDA
+ * Brown wire: SCL
+ *
+ * Copyright (C) 2009 Vassilis Varveropoulos
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+#include "baro_ets.h"
+#include "i2c.h"
+#include <math.h>
+
+#ifdef SITL
+#include "gps.h"
+#endif
+
+#define BARO_ETS_ADDR 0xE8
+#define BARO_ETS_REG 0x07
+#define BARO_ETS_SCALE 0.32
+#define BARO_ETS_OFFSET_MAX 30000
+#define BARO_ETS_OFFSET_MIN 10
+#define BARO_ETS_OFFSET_NBSAMPLES_INIT 20
+#define BARO_ETS_OFFSET_NBSAMPLES_AVRG 40
+
+// Global variables
+uint16_t baro_ets_adc;
+uint16_t baro_ets_offset;
+bool_t baro_ets_valid;
+float baro_ets_altitude;
+bool_t baro_ets_updated;
+bool_t baro_ets_enabled;
+float baro_ets_r;
+float baro_ets_sigma2;
+
+// Local variables
+volatile bool_t baro_ets_i2c_done;
+bool_t baro_ets_offset_init;
+uint32_t baro_ets_offset_tmp;
+uint16_t baro_ets_cnt;
+
+void baro_ets_init( void ) {
+  baro_ets_adc = 0;
+  baro_ets_altitude = 0.0;
+  baro_ets_offset = 0;
+  baro_ets_offset_tmp = 0;
+  baro_ets_i2c_done = TRUE;
+  baro_ets_valid = TRUE;
+  baro_ets_offset_init = FALSE;
+  baro_ets_enabled = TRUE;
+  baro_ets_updated = FALSE;
+  baro_ets_cnt = BARO_ETS_OFFSET_NBSAMPLES_INIT + 
BARO_ETS_OFFSET_NBSAMPLES_AVRG;
+  baro_ets_r = 20.0;
+  baro_ets_sigma2 = 1.0;
+  i2c0_buf[0] = 0;
+  i2c0_buf[1] = 0;  
+}
+
+void baro_ets_read( void ) {
+  // Initiate next read
+  i2c0_buf[0] = 0;
+  i2c0_buf[1] = 0;
+  i2c0_receive(BARO_ETS_ADDR, 2, &baro_ets_i2c_done);
+}      
+        
+void baro_ets_periodic( void ) {
+#ifndef SITL
+  // Read raw value
+  if (i2c0_status == I2C_IDLE) {
+    // Get raw altimeter from buffer
+    baro_ets_adc = ((uint16_t)(i2c0_buf[1]) << 8) | (uint16_t)(i2c0_buf[0]);
+    // Check if this is valid altimeter
+    if (baro_ets_adc == 0)
+      baro_ets_valid = FALSE;
+    else
+      baro_ets_valid = TRUE;
+  }
+  // Continue only if a new altimeter value was received  
+  if (baro_ets_valid) {
+    // Calculate offset average if not done already
+    if (!baro_ets_offset_init) {
+      --baro_ets_cnt;
+      // Check if averaging completed
+      if (baro_ets_cnt == 0) {
+        // Calculate average
+        baro_ets_offset = (uint16_t)(baro_ets_offset_tmp / 
BARO_ETS_OFFSET_NBSAMPLES_AVRG);
+        // Limit offset
+        if (baro_ets_offset < BARO_ETS_OFFSET_MIN)
+          baro_ets_offset = BARO_ETS_OFFSET_MIN;
+        if (baro_ets_offset > BARO_ETS_OFFSET_MAX)
+          baro_ets_offset = BARO_ETS_OFFSET_MAX;
+        baro_ets_offset_init = TRUE;
+      }
+      // Check if averaging needs to continue
+      else if (baro_ets_cnt <= BARO_ETS_OFFSET_NBSAMPLES_AVRG)
+        baro_ets_offset_tmp += baro_ets_adc;
+    }    
+    // Convert raw to m/s
+    if (baro_ets_offset_init)
+      baro_ets_altitude = BARO_ETS_SCALE * 
(float)(baro_ets_offset-baro_ets_adc);
+    else
+      baro_ets_altitude = 0.0;
+  } else {
+    baro_ets_altitude = 0.0;
+  }
+  // New value available
+  baro_ets_updated = TRUE;
+#else // SITL
+  baro_ets_adc = 0;
+  baro_ets_altitude = gps_alt / 100.0;
+  baro_ets_valid = TRUE;
+  baro_ets_updated = TRUE;
+#endif
+}
+


Property changes on: paparazzi3/trunk/sw/airborne/baro_ets.c
___________________________________________________________________
Added: svn:executable
   + *

Added: paparazzi3/trunk/sw/airborne/baro_ets.h
===================================================================
--- paparazzi3/trunk/sw/airborne/baro_ets.h                             (rev 0)
+++ paparazzi3/trunk/sw/airborne/baro_ets.h     2009-10-06 02:47:20 UTC (rev 
4232)
@@ -0,0 +1,25 @@
+/*
+ * Driver for the EagleTree Systems Altitude Sensor
+ */
+
+#ifndef BARO_ETS_H
+#define BARO_ETS_H
+
+#include "std.h"
+
+#define BARO_ETS_DT 0.05
+
+extern void baro_ets_periodic( void );
+extern void baro_ets_read( void );
+extern void baro_ets_init( void );
+
+extern uint16_t baro_ets_adc;
+extern uint16_t baro_ets_offset;
+extern bool_t baro_ets_valid;
+extern bool_t baro_ets_updated;
+extern bool_t baro_ets_enabled;
+extern float baro_ets_altitude;
+extern float baro_ets_r;
+extern float baro_ets_sigma2;
+
+#endif // BARO_ETS_H


Property changes on: paparazzi3/trunk/sw/airborne/baro_ets.h
___________________________________________________________________
Added: svn:executable
   + *

Modified: paparazzi3/trunk/sw/airborne/estimator.c
===================================================================
--- paparazzi3/trunk/sw/airborne/estimator.c    2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/estimator.c    2009-10-06 02:47:20 UTC (rev 
4232)
@@ -150,6 +150,12 @@
     R = baro_MS5534A_r;
     SIGMA2 = baro_MS5534A_sigma2;
   } else
+#elif defined(USE_BARO_ETS)
+  if (baro_ets_enabled) {
+    DT = BARO_ETS_DT;
+    R = baro_ets_r;
+    SIGMA2 = baro_ets_sigma2;
+  } else
 #endif
   {
     DT = GPS_DT;
@@ -204,9 +210,11 @@
   gps_east -= nav_utm_east0;
   gps_north -= nav_utm_north0;
 
+  EstimatorSetPosXY(gps_east, gps_north);
+#ifndef USE_BARO_ETS
   float falt = gps_alt / 100.;
-  EstimatorSetPosXY(gps_east, gps_north);
   EstimatorSetAlt(falt);
+#endif
   float fspeed = gps_gspeed / 100.;
   float fclimb = gps_climb / 100.;
   float fcourse = RadOfDeg(gps_course / 10.);

Modified: paparazzi3/trunk/sw/airborne/estimator.h
===================================================================
--- paparazzi3/trunk/sw/airborne/estimator.h    2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/estimator.h    2009-10-06 02:47:20 UTC (rev 
4232)
@@ -36,6 +36,10 @@
 #include "baro_MS5534A.h"
 #endif
 
+#ifdef USE_BARO_ETS
+#include "baro_ets.h"
+#endif
+
 /* position in meters */
 extern float estimator_x;
 extern float estimator_y;
@@ -87,7 +91,7 @@
 #ifdef ALT_KALMAN
 #define EstimatorSetPosXY(x, y) { estimator_x = x; estimator_y = y; }
 
-#ifdef USE_BARO_MS5534A
+#if defined(USE_BARO_MS5534A) || defined(USE_BARO_ETS)
 /* Kalman filter cannot be disabled in this mode (no z_dot) */
 #define EstimatorSetAlt(z) alt_kalman(z)
 #else /* USE_BARO_MS5534A */

Modified: paparazzi3/trunk/sw/airborne/fw_v_ctl.c
===================================================================
--- paparazzi3/trunk/sw/airborne/fw_v_ctl.c     2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/fw_v_ctl.c     2009-10-06 02:47:20 UTC (rev 
4232)
@@ -80,14 +80,16 @@
 
 #ifdef USE_AIRSPEED
 float v_ctl_auto_airspeed_setpoint;
-float v_ctl_auto_airspeed_pitch_pgain;
-float v_ctl_auto_airspeed_throttle_pgain;
-float v_ctl_auto_airspeed_throttle_igain;
-
-float v_ctl_auto_airspeed_throttle_sum_err;
-#define V_CTL_AUTO_AIRSPEED_THROTTLE_MAX_SUM_ERR 100
-
-inline void v_ctl_airspeed_loop( void );
+float v_ctl_auto_airspeed_controlled;
+float v_ctl_auto_airspeed_pgain;
+float v_ctl_auto_airspeed_igain;
+float v_ctl_auto_airspeed_sum_err;
+float v_ctl_auto_groundspeed_setpoint;
+float v_ctl_auto_groundspeed_pgain;
+float v_ctl_auto_groundspeed_igain;
+float v_ctl_auto_groundspeed_sum_err;
+#define V_CTL_AUTO_AIRSPEED_MAX_SUM_ERR 200
+#define V_CTL_AUTO_GROUNDSPEED_MAX_SUM_ERR 100
 #endif
 
 
@@ -129,11 +131,15 @@
 
 #ifdef USE_AIRSPEED
   v_ctl_auto_airspeed_setpoint = V_CTL_AUTO_AIRSPEED_SETPOINT;
-  v_ctl_auto_airspeed_pitch_pgain = V_CTL_AUTO_AIRSPEED_PITCH_PGAIN;
-  v_ctl_auto_airspeed_throttle_pgain = V_CTL_AUTO_AIRSPEED_THROTTLE_PGAIN;
-  v_ctl_auto_airspeed_throttle_igain = V_CTL_AUTO_AIRSPEED_THROTTLE_IGAIN;
+  v_ctl_auto_airspeed_controlled = V_CTL_AUTO_AIRSPEED_SETPOINT;
+  v_ctl_auto_airspeed_pgain = V_CTL_AUTO_AIRSPEED_PGAIN;
+  v_ctl_auto_airspeed_igain = V_CTL_AUTO_AIRSPEED_IGAIN;
+  v_ctl_auto_airspeed_sum_err = 0.;
 
-  v_ctl_auto_airspeed_throttle_sum_err = 0.;
+  v_ctl_auto_groundspeed_setpoint = V_CTL_AUTO_GROUNDSPEED_SETPOINT;
+  v_ctl_auto_groundspeed_pgain = V_CTL_AUTO_GROUNDSPEED_PGAIN;
+  v_ctl_auto_groundspeed_igain = V_CTL_AUTO_GROUNDSPEED_IGAIN;
+  v_ctl_auto_groundspeed_sum_err = 0.;
 #endif
 
   v_ctl_throttle_setpoint = 0;
@@ -182,6 +188,9 @@
  * auto throttle inner loop
  * \brief 
  */
+
+#ifndef USE_AIRSPEED
+
 inline static void v_ctl_climb_auto_throttle_loop(void) {
   static float last_err;
 
@@ -198,18 +207,6 @@
   /* pitch pre-command */
   float v_ctl_pitch_of_vz = (v_ctl_climb_setpoint + d_err * 
v_ctl_auto_throttle_pitch_of_vz_dgain) * v_ctl_auto_throttle_pitch_of_vz_pgain;
 
-#ifdef USE_AIRSPEED
-  float err_airspeed = (v_ctl_auto_airspeed_setpoint - estimator_airspeed);
-
-  v_ctl_auto_airspeed_throttle_sum_err += err_airspeed;
-  BoundAbs(v_ctl_auto_airspeed_throttle_sum_err, 
V_CTL_AUTO_AIRSPEED_THROTTLE_MAX_SUM_ERR);
-
-  float v_ctl_auto_airspeed_pitch_of_airspeed = (err_airspeed) * 
v_ctl_auto_airspeed_pitch_pgain;
-  float v_ctl_auto_airspeed_throttle_of_airspeed = (err_airspeed + 
v_ctl_auto_airspeed_throttle_sum_err * v_ctl_auto_airspeed_throttle_igain) * 
v_ctl_auto_airspeed_throttle_pgain;
-
-  controlled_throttle += v_ctl_auto_airspeed_throttle_of_airspeed;
-#endif
-
 #if defined AGR_CLIMB
   switch (v_ctl_auto_throttle_submode) {
   case V_CTL_AUTO_THROTTLE_AGRESSIVE:
@@ -251,14 +248,50 @@
   } /* switch submode */
 #endif
 
-#ifdef USE_AIRSPEED
-  nav_pitch += v_ctl_auto_airspeed_pitch_of_airspeed;
-#endif
+  v_ctl_throttle_setpoint = TRIM_UPPRZ(f_throttle * MAX_PPRZ);
+}
 
+#else // USE_AIRSPEED
+
+inline static void v_ctl_climb_auto_throttle_loop(void) {
+  float f_throttle = 0;
+  float controlled_throttle;
+  float v_ctl_pitch_of_vz;
+
+  // Pitch control (input: rate of climb error, output: pitch setpoint)
+  float err  = estimator_z_dot - v_ctl_climb_setpoint;
+  v_ctl_auto_pitch_sum_err += err;
+  BoundAbs(v_ctl_auto_pitch_sum_err, V_CTL_AUTO_PITCH_MAX_SUM_ERR);
+  v_ctl_pitch_of_vz = v_ctl_auto_pitch_pgain *
+    (err + v_ctl_auto_pitch_igain * v_ctl_auto_pitch_sum_err);
+
+  // Ground speed control loop (input: groundspeed error, output: airspeed 
controlled)
+  float err_groundspeed = (v_ctl_auto_groundspeed_setpoint - 
estimator_hspeed_mod);
+  v_ctl_auto_groundspeed_sum_err += err_groundspeed;
+  BoundAbs(v_ctl_auto_groundspeed_sum_err, V_CTL_AUTO_GROUNDSPEED_MAX_SUM_ERR);
+  v_ctl_auto_airspeed_controlled = (err_groundspeed + 
v_ctl_auto_groundspeed_sum_err * v_ctl_auto_groundspeed_igain) * 
v_ctl_auto_groundspeed_pgain;
+
+  // Do not allow controlled airspeed below the setpoint
+  if (v_ctl_auto_airspeed_controlled < v_ctl_auto_airspeed_setpoint) {
+    v_ctl_auto_airspeed_controlled = v_ctl_auto_airspeed_setpoint;
+    v_ctl_auto_groundspeed_sum_err = 
v_ctl_auto_airspeed_controlled/(v_ctl_auto_groundspeed_pgain*v_ctl_auto_groundspeed_igain);
 // reset integrator of ground speed loop
+  }
+
+  // Airspeed control loop (input: airspeed controlled, output: throttle 
controlled)
+  float err_airspeed = (v_ctl_auto_airspeed_controlled - estimator_airspeed);
+  v_ctl_auto_airspeed_sum_err += err_airspeed;
+  BoundAbs(v_ctl_auto_airspeed_sum_err, V_CTL_AUTO_AIRSPEED_MAX_SUM_ERR);
+  controlled_throttle = (err_airspeed + v_ctl_auto_airspeed_sum_err * 
v_ctl_auto_airspeed_igain) * v_ctl_auto_airspeed_pgain;
+
+  f_throttle = controlled_throttle;
+  nav_pitch = v_ctl_pitch_of_vz;
   v_ctl_throttle_setpoint = TRIM_UPPRZ(f_throttle * MAX_PPRZ);
+  Bound(nav_pitch, V_CTL_AUTO_PITCH_MIN_PITCH, V_CTL_AUTO_PITCH_MAX_PITCH);
 }
 
+#endif // USE_AIRSPEED
 
+
 /** 
  * auto pitch inner loop
  * \brief computes a nav_pitch from a climb_setpoint given a fixed throttle

Modified: paparazzi3/trunk/sw/airborne/fw_v_ctl.h
===================================================================
--- paparazzi3/trunk/sw/airborne/fw_v_ctl.h     2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/fw_v_ctl.h     2009-10-06 02:47:20 UTC (rev 
4232)
@@ -90,9 +90,14 @@
 #ifdef USE_AIRSPEED
 /* "airspeed" inner loop parameters */
 extern float v_ctl_auto_airspeed_setpoint;
-extern float v_ctl_auto_airspeed_pitch_pgain;
-extern float v_ctl_auto_airspeed_throttle_pgain;
-extern float v_ctl_auto_airspeed_throttle_igain;
+extern float v_ctl_auto_airspeed_controlled;
+extern float v_ctl_auto_airspeed_pgain;
+extern float v_ctl_auto_airspeed_igain;
+extern float v_ctl_auto_airspeed_sum_err;
+extern float v_ctl_auto_groundspeed_setpoint;
+extern float v_ctl_auto_groundspeed_pgain;
+extern float v_ctl_auto_groundspeed_igain;
+extern float v_ctl_auto_groundspeed_sum_err;
 #endif
 
 /** Computes throttle_slewed from throttle_setpoint */

Modified: paparazzi3/trunk/sw/airborne/main_ap.c
===================================================================
--- paparazzi3/trunk/sw/airborne/main_ap.c      2009-10-05 06:56:52 UTC (rev 
4231)
+++ paparazzi3/trunk/sw/airborne/main_ap.c      2009-10-06 02:47:20 UTC (rev 
4232)
@@ -127,6 +127,14 @@
 #include "usb_serial.h"
 #endif
 
+#ifdef USE_AIRSPEED_ETS
+#include "airspeed_ets.h"
+#endif // USE_AIRSPEED_ETS
+
+#ifdef USE_BARO_ETS
+#include "baro_ets.h"
+#endif // USE_BARO_ETS
+
 /*code added by Haiyang Chao for using Xsens IMU for fixed wing UAV 20080804*/
 #ifdef UGEAR
 #include "osam_imu_ugear.h"
@@ -581,6 +589,29 @@
   if (!_20Hz)
 #endif
     {
+
+    // I2C scheduler
+    switch (_20Hz) {
+      case 0:
+#ifdef USE_AIRSPEED_ETS
+        airspeed_ets_periodic(); // process airspeed
+#endif // USE_AIRSPEED_ETS
+#ifdef USE_BARO_ETS
+        baro_ets_read(); // initiate next i2c read
+#endif // USE_BARO_ETS
+        break;
+      case 1:
+#ifdef USE_BARO_ETS
+        baro_ets_periodic(); // process altitude
+#endif // USE_BARO_ETS
+#ifdef USE_AIRSPEED_ETS
+        airspeed_ets_read(); // initiate next i2c read
+#endif // USE_AIRSPEED_ETS
+        break;
+      case 2:
+        break;
+    }
+
 #if defined GYRO
       gyro_update();
 #endif
@@ -668,6 +699,14 @@
   i2c1_init();
 #endif
 
+#ifdef USE_AIRSPEED_ETS
+  airspeed_ets_init();
+#endif
+
+#ifdef USE_BARO_ETS
+  baro_ets_init();
+#endif
+
 #ifdef USE_ADC_GENERIC
   adc_generic_init();
 #endif
@@ -887,6 +926,13 @@
       }
     }
   }
+#elif defined(USE_BARO_ETS)
+  if (baro_ets_updated) {
+    baro_ets_updated = FALSE;
+    if (baro_ets_valid) {
+      EstimatorSetAlt(baro_ets_altitude);
+    }
+  }
 #endif
 
   if (inter_mcu_received_fbw) {





reply via email to

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