paparazzi-commits
[Top][All Lists]
Advanced

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

[paparazzi-commits] [6186] Have the good old MS5534A as module.


From: Martin Mueller
Subject: [paparazzi-commits] [6186] Have the good old MS5534A as module.
Date: Tue, 19 Oct 2010 20:54:52 +0000

Revision: 6186
          http://svn.sv.gnu.org/viewvc/?view=rev&root=paparazzi&revision=6186
Author:   mmm
Date:     2010-10-19 20:54:52 +0000 (Tue, 19 Oct 2010)
Log Message:
-----------
Have the good old MS5534A as module. It still works :-)

Modified Paths:
--------------
    paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml
    paparazzi3/trunk/sw/airborne/ap_downlink.h
    paparazzi3/trunk/sw/airborne/main_ap.c

Added Paths:
-----------
    paparazzi3/trunk/conf/autopilot/subsystems/fixedwing/spi.makefile
    paparazzi3/trunk/conf/modules/baro_MS5534A.xml
    paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.c
    paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.h

Removed Paths:
-------------
    paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.c
    paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.h

Modified: paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml
===================================================================
--- paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml  2010-10-19 
19:26:31 UTC (rev 6185)
+++ paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml  2010-10-19 
20:54:52 UTC (rev 6186)
@@ -24,7 +24,6 @@
       <define name="ALT_KALMAN"/>
       <define name="WIND_INFO"/>
       <define name="WIND_INFO_RET"/>
-      <define name="USE_I2C0"/>
     </target>
 
     <subsystem name="radio_control"    type="ppm"/>
@@ -42,7 +41,7 @@
       <param name="GPS_BAUD"           value="B38400"/>
     </subsystem>
     <subsystem name="navigation"/>
-    <subsystem name="i2c"/>
+    <subsystem name="spi"/>
   </firmware>
 
   <firmware name="setup">
@@ -55,9 +54,10 @@
 
   <!-- modules -->
   <modules>
-    <load name="baro_bmp.xml"/>
+    <load name="baro_MS5534A.xml"/>
+    <!--load name="baro_bmp.xml"/>
     <load name="baro_scp_i2c.xml"/>
-    <!--load name="light_temt.xml"/>
+    <load name="light_temt.xml"/>
     <load name="humid_hih.xml"/>
     <load name="temp_tmp102.xml"/>
     <load name="temp_lm75.xml"/>

Added: paparazzi3/trunk/conf/autopilot/subsystems/fixedwing/spi.makefile
===================================================================
--- paparazzi3/trunk/conf/autopilot/subsystems/fixedwing/spi.makefile           
                (rev 0)
+++ paparazzi3/trunk/conf/autopilot/subsystems/fixedwing/spi.makefile   
2010-10-19 20:54:52 UTC (rev 6186)
@@ -0,0 +1,5 @@
+#generic spi driver
+$(TARGET).CFLAGS += -DUSE_SPI
+
+ap.srcs += spi.c $(SRC_ARCH)/spi_hw.c
+sim.srcs += spi.c $(SRC_ARCH)/spi_hw.c

Added: paparazzi3/trunk/conf/modules/baro_MS5534A.xml
===================================================================
--- paparazzi3/trunk/conf/modules/baro_MS5534A.xml                              
(rev 0)
+++ paparazzi3/trunk/conf/modules/baro_MS5534A.xml      2010-10-19 20:54:52 UTC 
(rev 6186)
@@ -0,0 +1,21 @@
+<!DOCTYPE module SYSTEM "module.dtd">
+
+<module name="baro_MS5534A" dir="sensors">
+  <header>
+    <file name="baro_MS5534A.h"/>
+  </header>
+  <init fun="baro_MS5534A_init()"/>
+  <periodic fun="baro_MS5534A_send()" freq="20"/>
+  <event fun="baro_MS5534A_event()"/>
+  <makefile>
+    <file name="baro_MS5534A.c"/>
+    <flag name="USE_BARO_MS5534A"/>
+    <flag name="USE_SPI_SLAVE0"/>
+    <flag name="SPI_MASTER"/>
+    <define name="BARO_MS5534A_W1" value="0xAC20"/>
+    <define name="BARO_MS5534A_W2" value="0x87D9"/>
+    <define name="BARO_MS5534A_W3" value="0x8D9C"/>
+    <define name="BARO_MS5534A_W4" value="0xB080"/>
+  </makefile>
+</module>
+

Modified: paparazzi3/trunk/sw/airborne/ap_downlink.h
===================================================================
--- paparazzi3/trunk/sw/airborne/ap_downlink.h  2010-10-19 19:26:31 UTC (rev 
6185)
+++ paparazzi3/trunk/sw/airborne/ap_downlink.h  2010-10-19 20:54:52 UTC (rev 
6186)
@@ -181,7 +181,7 @@
 #endif
 
 #ifdef USE_BARO_MS5534A
-#include "baro_MS5534A.h"
+//#include "baro_MS5534A.h"
 #define PERIODIC_SEND_BARO_MS5534A(_chan) DOWNLINK_SEND_BARO_MS5534A(_chan, 
&baro_MS5534A_pressure, &baro_MS5534A_temp, &baro_MS5534A_z)
 #else
 #define PERIODIC_SEND_BARO_MS5534A(_chan) {}

Deleted: paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.c
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.c      2010-10-19 
19:26:31 UTC (rev 6185)
+++ paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.c      2010-10-19 
20:54:52 UTC (rev 6186)
@@ -1,251 +0,0 @@
-/*
- * $Id$
- *  
- * Copyright (C) 2007  ENAC
- *
- * 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. 
- *
- */
-
-/** \file baro_MS5534A.c
- *  \brief Handling of the MS5534a pressure sensor
- *
- */
-
-#include "baro_MS5534A.h"
-#include "spi.h"
-#include "uart.h"
-#ifndef BARO_NO_DOWNLINK
-#include "ap_downlink.h"
-#endif
-#include "nav.h"
-
-bool_t baro_MS5534A_do_reset;
-uint32_t baro_MS5534A_pressure;
-uint16_t baro_MS5534A_temp;
-bool_t baro_MS5534A_available;
-bool_t alt_baro_enabled;
-uint32_t baro_MS5534A_ground_pressure;
-float baro_MS5534A_r;
-float baro_MS5534A_sigma2;
-float baro_MS5534A_z;
-
-
-#define STATUS_INIT1               0
-#define STATUS_INIT2               1
-#define STATUS_INIT3               2
-#define STATUS_INIT4               3
-#define STATUS_MEASURE_PRESSURE    4
-#define STATUS_MEASURE_TEMPERATURE 5
-#define STATUS_RESET               6
-
-static uint8_t status;
-static bool_t status_read_data;
-static uint16_t words[4];
-
-#define InitStatus() (status <= STATUS_INIT4)
-
-#define NextStatus() { \
-  if (status_read_data) { \
-    status++; if (status > STATUS_MEASURE_TEMPERATURE) status = 
STATUS_MEASURE_PRESSURE; \
-  }; \
-  status_read_data = !status_read_data; \
-}
-
-#define CMD_INIT        0x1D
-#define CMD_MEASUREMENT 0x0F
-
-#define CMD_W1          0x50
-#define CMD_W2          0x60
-#define CMD_W3          0x90
-#define CMD_W4          0xA0
-#define CMD_PRESSURE    0x40
-#define CMD_TEMPERATURE 0x20
-static uint8_t cmds[6] = {CMD_W1, CMD_W2, CMD_W3, CMD_W4, CMD_PRESSURE, 
CMD_TEMPERATURE};
-static uint8_t reset[3] = {0x15, 0x55, 0x40};
-
-
-
-static uint8_t buf_input[3];
-static uint8_t buf_output[3];
-
-#define Uint16(buf_input) (buf_input[0] << 8 | buf_input[1])
-
-/* PWM prescaler, set PWM input clock to 15MHz, PWM_CLK = PCLK / PWM_PRESCALER 
*/
-
-#if (PCLK == 15000000)
-#define PWM_PRESCALER   1
-#else
-
-#if (PCLK == 30000000)
-#define PWM_PRESCALER   2
-#else
-
-#if (PCLK == 60000000)
-#define PWM_PRESCALER   4
-#else
-
-#error unknown PCLK frequency
-#endif
-#endif
-#endif
-
-#define MS5534A_MCLK 32768
-#define PWM_PERIOD ((PCLK / PWM_PRESCALER) / MS5534A_MCLK)
-#define PWM_DUTY (PWM_PERIOD / 2)
-
-
-static void calibration( void );
-
-void baro_MS5534A_init( void ) {
-  /* 32768Hz on PWM2 */
-  /* Configure P0.7 pin as PWM */
-  PINSEL0 &= ~(_BV(14));
-  PINSEL0 |= _BV(15);
-
-  /* No prescaler */
-  PWMPR = PWM_PRESCALER-1;
-
-  /* To get 32768Hz from a base frequency of 15MHz */
-  PWMMR0 = PWM_PERIOD;
-  PWMMR2 = PWM_DUTY;
-
-  PWMLER = PWMLER_LATCH0 | PWMLER_LATCH2;
-  PWMTCR = PWMTCR_COUNTER_ENABLE | PWMTCR_PWM_ENABLE;
-  PWMPCR = PWMPCR_ENA2;
-
-#ifdef BARO_MS5534A_W1
-  words[0] = BARO_MS5534A_W1;
-  words[1] = BARO_MS5534A_W2;
-  words[2] = BARO_MS5534A_W3;
-  words[3] = BARO_MS5534A_W4;
-
-  status = STATUS_MEASURE_PRESSURE;
-  status_read_data = FALSE;
-
-  calibration();
-#else
-  status = STATUS_INIT1;
-  status_read_data = FALSE;
-#endif
-
-
-
-  baro_MS5534A_available = FALSE;
-  alt_baro_enabled = FALSE;
-
-  baro_MS5534A_ground_pressure = 101300;
-  baro_MS5534A_r = 20.;
-  baro_MS5534A_sigma2 = 1;
-  baro_MS5534A_do_reset = FALSE;
-}
-
-void baro_MS5534A_reset( void ) {
-  status = STATUS_INIT1;
-  status_read_data = FALSE;
-}
-
-/* To be called not faster than 30Hz */
-void baro_MS5534A_send(void) {
-  if (!SpiCheckAvailable()) {
-    SpiOverRun();
-    return;
-  }
-
-  if (status == STATUS_RESET) {
-    uint8_t i;
-    for(i = 0; i < 3; i++)
-      buf_output[i] = reset[i];
-    spi_buffer_length = 3;
-  } else {
-    if (status_read_data) {
-      buf_output[0] = buf_output[1] = 0;
-    } else {
-      buf_output[0] = (InitStatus() ? CMD_INIT : CMD_MEASUREMENT);
-      buf_output[1] = cmds[status];
-    }
-    spi_buffer_length = 2;
-  }
-
-  spi_buffer_input = (uint8_t*)&buf_input;
-  spi_buffer_output = (uint8_t*)&buf_output;
-  if (status_read_data)
-    SpiSetCPHA();
-  else
-    SpiClrCPHA();
-  SpiStart();
-}
-
-static uint16_t d1, d2;
-static uint16_t c1, c2, c3, c4, ut1, c6;
-
-
-static void calibration( void ) {
-  /* End of init, configuration (page 11) */
-  c1 = words[0] >> 1;
-  c2 = ((words[2] & 0x3f) << 6) | (words[3] & 0x3f);
-  c3 = words[3] >> 6;
-  c4 = words[2] >> 6;
-  uint16_t c5 = ((words[0] & 0x1) << 10) | (words[1] >> 6);
-  c6 = words[1] & 0x3f;
-  
-  ut1 = (c5 << 3) + 20224;
-  
-#ifndef BARO_NO_DOWNLINK
-  DOWNLINK_SEND_BARO_WORDS(DefaultChannel, &words[0], &words[1], &words[2], 
&words[3]);
-#endif
-}
-
-
-
-/* Handle the SPI message, i.e. store the received values in variables */
-void baro_MS5534A_event_task( void ) {
-  if (status_read_data) {
-    switch (status) {
-    case STATUS_MEASURE_PRESSURE:
-      d1 = Uint16(buf_input);
-      break;
-    case STATUS_MEASURE_TEMPERATURE:
-      d2 = Uint16(buf_input);
-      /* Compute pressure and temp (page 10) */
-      int16_t dT = d2 - ut1;
-      baro_MS5534A_temp = 200 + (dT*(c6+50)) / (1 << 10);
-      int16_t off = c2*4 + ((c4-512)*dT)/(1 << 12);
-      uint32_t sens = c1 + (c3*dT)/(1<<10) + 24576;
-      uint16_t x = (sens*(d1-7168))/(1<<14) - off;
-      // baro_MS5534A = ((x*10)>>5) + 250*10;
-      baro_MS5534A_pressure = ((x*100)>>5) + 250*100;
-      baro_MS5534A_available = TRUE;
-
-      break;
-     case STATUS_RESET:
-       break;
-    default: /* Init status */
-      words[status] = Uint16(buf_input);
-      if (status == STATUS_INIT4) {
-       calibration();
-      }
-    }
-  } /* else nothing to read */
-
-  NextStatus();
-  if (!status_read_data) {
-   /* Ask next conversion now */
-    baro_MS5534A_send();
-  }
-}

Deleted: paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.h
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.h      2010-10-19 
19:26:31 UTC (rev 6185)
+++ paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.h      2010-10-19 
20:54:52 UTC (rev 6186)
@@ -1,58 +0,0 @@
-/*
- * $Id$
- *  
- * Copyright (C) 2007  ENAC
- *
- * 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. 
- *
- */
-
-/** \file baro_MS5534A.h
- *  \brief Handling of the MS5534a pressure sensor
- *
- */
-
-#ifndef BARO_MS5534A_H
-#define BARO_MS5534A_H
-
-#include "std.h"
-
-#ifdef USE_BARO_MS5534A
-
-extern bool_t baro_MS5534A_do_reset;
-extern bool_t baro_MS5534A_available;
-extern uint32_t baro_MS5534A_pressure;
-extern uint16_t baro_MS5534A_temp;
-extern bool_t alt_baro_enabled;
-extern uint32_t baro_MS5534A_ground_pressure;
-extern float baro_MS5534A_r;
-extern float baro_MS5534A_sigma2;
-extern float baro_MS5534A_z;
-
-void baro_MS5534A_init(void);
-void baro_MS5534A_reset(void);
-
-/* To be called not faster than 30Hz */
-void baro_MS5534A_send(void);
-
-/* Set baro_MS5534A_available when pressure and temp are readable */
-void baro_MS5534A_event_task( void );
-
-#endif // USE_BARO_MS5534A
-
-#endif // BARO_MS5534A_H

Modified: paparazzi3/trunk/sw/airborne/main_ap.c
===================================================================
--- paparazzi3/trunk/sw/airborne/main_ap.c      2010-10-19 19:26:31 UTC (rev 
6185)
+++ paparazzi3/trunk/sw/airborne/main_ap.c      2010-10-19 20:54:52 UTC (rev 
6186)
@@ -91,10 +91,6 @@
 #include "srf08.h"
 #endif
 
-#ifdef USE_BARO_MS5534A
-#include "baro_MS5534A.h"
-#endif
-
 #ifdef USE_MAX11040
 #include "max11040.h"
 #endif
@@ -573,12 +569,6 @@
 #error "Only 20 and 60 allowed for CONTROL_RATE"
 #endif
 
-#ifdef USE_BARO_MS5534A
-  if (!_20Hz) {
-    baro_MS5534A_send();
-  }
-#endif
-
 #ifdef USE_I2C0
   // I2C0 scheduler
   switch (_20Hz) {
@@ -763,10 +753,6 @@
   IO0SET = _BV(AEROCOMM_DATA_PIN);
 #endif
 
-#ifdef USE_BARO_MS5534A
-  baro_MS5534A_init();
-#endif
-
   power_switch = FALSE;
 
   /************ Multi-uavs status ***************/
@@ -892,20 +878,7 @@
   }
 #endif
 
-#ifdef USE_BARO_MS5534A
-  if (spi_message_received) {
-    /* Got a message on SPI. */
-    spi_message_received = FALSE;
-    baro_MS5534A_event_task();
-    if (baro_MS5534A_available) {
-      baro_MS5534A_available = FALSE;
-      baro_MS5534A_z = ground_alt +((float)baro_MS5534A_ground_pressure - 
baro_MS5534A_pressure)*0.084;
-      if (alt_baro_enabled) {
-       EstimatorSetAlt(baro_MS5534A_z);
-      }
-    }
-  }
-#elif defined(USE_BARO_ETS)
+#if defined(USE_BARO_ETS)
   if (baro_ets_updated) {
     baro_ets_updated = FALSE;
     if (baro_ets_valid) {

Copied: paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.c (from rev 
6185, paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.c                 
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.c 2010-10-19 
20:54:52 UTC (rev 6186)
@@ -0,0 +1,269 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2007  ENAC
+ *
+ * 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. 
+ *
+ */
+
+/** \file baro_MS5534A.c
+ *  \brief Handling of the MS5534a pressure sensor
+ *
+ * uses: MOSI, MISO, SCK and 32kHz @ P0.7 with 5V for the -A type
+ */
+
+#include "baro_MS5534A.h"
+#include "spi.h"
+#include "uart.h"
+#ifndef BARO_NO_DOWNLINK
+#include "ap_downlink.h"
+#endif
+#include "nav.h"
+#include "estimator.h"
+
+bool_t baro_MS5534A_do_reset;
+uint32_t baro_MS5534A_pressure;
+uint16_t baro_MS5534A_temp;
+bool_t baro_MS5534A_available;
+bool_t alt_baro_enabled;
+uint32_t baro_MS5534A_ground_pressure;
+float baro_MS5534A_r;
+float baro_MS5534A_sigma2;
+float baro_MS5534A_z;
+
+
+#define STATUS_INIT1               0
+#define STATUS_INIT2               1
+#define STATUS_INIT3               2
+#define STATUS_INIT4               3
+#define STATUS_MEASURE_PRESSURE    4
+#define STATUS_MEASURE_TEMPERATURE 5
+#define STATUS_RESET               6
+
+static uint8_t status;
+static bool_t status_read_data;
+static uint16_t words[4];
+
+#define InitStatus() (status <= STATUS_INIT4)
+
+#define NextStatus() { \
+  if (status_read_data) { \
+    status++; if (status > STATUS_MEASURE_TEMPERATURE) status = 
STATUS_MEASURE_PRESSURE; \
+  }; \
+  status_read_data = !status_read_data; \
+}
+
+#define CMD_INIT        0x1D
+#define CMD_MEASUREMENT 0x0F
+
+#define CMD_W1          0x50
+#define CMD_W2          0x60
+#define CMD_W3          0x90
+#define CMD_W4          0xA0
+#define CMD_PRESSURE    0x40
+#define CMD_TEMPERATURE 0x20
+static uint8_t cmds[6] = {CMD_W1, CMD_W2, CMD_W3, CMD_W4, CMD_PRESSURE, 
CMD_TEMPERATURE};
+static uint8_t reset[3] = {0x15, 0x55, 0x40};
+
+
+
+static uint8_t buf_input[3];
+static uint8_t buf_output[3];
+
+#define Uint16(buf_input) (buf_input[0] << 8 | buf_input[1])
+
+/* PWM prescaler, set PWM input clock to 15MHz, PWM_CLK = PCLK / PWM_PRESCALER 
*/
+
+#if (PCLK == 15000000)
+#define PWM_PRESCALER   1
+#else
+
+#if (PCLK == 30000000)
+#define PWM_PRESCALER   2
+#else
+
+#if (PCLK == 60000000)
+#define PWM_PRESCALER   4
+#else
+
+#error unknown PCLK frequency
+#endif
+#endif
+#endif
+
+#define MS5534A_MCLK 32768
+#define PWM_PERIOD ((PCLK / PWM_PRESCALER) / MS5534A_MCLK)
+#define PWM_DUTY (PWM_PERIOD / 2)
+
+
+static void calibration( void );
+
+void baro_MS5534A_init( void ) {
+  /* 32768Hz on PWM2 */
+  /* Configure P0.7 pin as PWM */
+  PINSEL0 &= ~(_BV(14));
+  PINSEL0 |= _BV(15);
+
+  /* No prescaler */
+  PWMPR = PWM_PRESCALER-1;
+
+  /* To get 32768Hz from a base frequency of 15MHz */
+  PWMMR0 = PWM_PERIOD;
+  PWMMR2 = PWM_DUTY;
+
+  PWMLER = PWMLER_LATCH0 | PWMLER_LATCH2;
+  PWMTCR = PWMTCR_COUNTER_ENABLE | PWMTCR_PWM_ENABLE;
+  PWMPCR = PWMPCR_ENA2;
+
+#ifdef BARO_MS5534A_W1
+  words[0] = BARO_MS5534A_W1;
+  words[1] = BARO_MS5534A_W2;
+  words[2] = BARO_MS5534A_W3;
+  words[3] = BARO_MS5534A_W4;
+
+  status = STATUS_MEASURE_PRESSURE;
+  status_read_data = FALSE;
+
+  calibration();
+#else
+  status = STATUS_INIT1;
+  status_read_data = FALSE;
+#endif
+
+
+
+  baro_MS5534A_available = FALSE;
+  alt_baro_enabled = FALSE;
+
+  baro_MS5534A_ground_pressure = 101300;
+  baro_MS5534A_r = 20.;
+  baro_MS5534A_sigma2 = 1;
+  baro_MS5534A_do_reset = FALSE;
+}
+
+void baro_MS5534A_reset( void ) {
+  status = STATUS_INIT1;
+  status_read_data = FALSE;
+}
+
+/* To be called not faster than 30Hz */
+void baro_MS5534A_send(void) {
+  if (!SpiCheckAvailable()) {
+    SpiOverRun();
+    return;
+  }
+
+  if (status == STATUS_RESET) {
+    uint8_t i;
+    for(i = 0; i < 3; i++)
+      buf_output[i] = reset[i];
+    spi_buffer_length = 3;
+  } else {
+    if (status_read_data) {
+      buf_output[0] = buf_output[1] = 0;
+    } else {
+      buf_output[0] = (InitStatus() ? CMD_INIT : CMD_MEASUREMENT);
+      buf_output[1] = cmds[status];
+    }
+    spi_buffer_length = 2;
+  }
+
+  spi_buffer_input = (uint8_t*)&buf_input;
+  spi_buffer_output = (uint8_t*)&buf_output;
+  if (status_read_data)
+    SpiSetCPHA();
+  else
+    SpiClrCPHA();
+  SpiStart();
+}
+
+static uint16_t d1, d2;
+static uint16_t c1, c2, c3, c4, ut1, c6;
+
+
+static void calibration( void ) {
+  /* End of init, configuration (page 11) */
+  c1 = words[0] >> 1;
+  c2 = ((words[2] & 0x3f) << 6) | (words[3] & 0x3f);
+  c3 = words[3] >> 6;
+  c4 = words[2] >> 6;
+  uint16_t c5 = ((words[0] & 0x1) << 10) | (words[1] >> 6);
+  c6 = words[1] & 0x3f;
+  
+  ut1 = (c5 << 3) + 20224;
+  
+#ifndef BARO_NO_DOWNLINK
+  DOWNLINK_SEND_BARO_WORDS(DefaultChannel, &words[0], &words[1], &words[2], 
&words[3]);
+#endif
+}
+
+
+
+/* Handle the SPI message, i.e. store the received values in variables */
+void baro_MS5534A_event_task( void ) {
+  if (status_read_data) {
+    switch (status) {
+    case STATUS_MEASURE_PRESSURE:
+      d1 = Uint16(buf_input);
+      break;
+    case STATUS_MEASURE_TEMPERATURE:
+      d2 = Uint16(buf_input);
+      /* Compute pressure and temp (page 10) */
+      int16_t dT = d2 - ut1;
+      baro_MS5534A_temp = 200 + (dT*(c6+50)) / (1 << 10);
+      int16_t off = c2*4 + ((c4-512)*dT)/(1 << 12);
+      uint32_t sens = c1 + (c3*dT)/(1<<10) + 24576;
+      uint16_t x = (sens*(d1-7168))/(1<<14) - off;
+      // baro_MS5534A = ((x*10)>>5) + 250*10;
+      baro_MS5534A_pressure = ((x*100)>>5) + 250*100;
+      baro_MS5534A_available = TRUE;
+
+      break;
+     case STATUS_RESET:
+       break;
+    default: /* Init status */
+      words[status] = Uint16(buf_input);
+      if (status == STATUS_INIT4) {
+       calibration();
+      }
+    }
+  } /* else nothing to read */
+
+  NextStatus();
+  if (!status_read_data) {
+   /* Ask next conversion now */
+    baro_MS5534A_send();
+  }
+}
+
+void baro_MS5534A_event( void ) {
+  if (spi_message_received) {
+    /* Got a message on SPI. */
+    spi_message_received = FALSE;
+    baro_MS5534A_event_task();
+    if (baro_MS5534A_available) {
+      baro_MS5534A_available = FALSE;
+      baro_MS5534A_z = ground_alt +((float)baro_MS5534A_ground_pressure - 
baro_MS5534A_pressure)*0.084;
+      if (alt_baro_enabled) {
+       EstimatorSetAlt(baro_MS5534A_z);
+      }
+    }
+  }
+}
+

Copied: paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.h (from rev 
6185, paparazzi3/trunk/sw/airborne/arch/lpc21/baro_MS5534A.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.h                 
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/sensors/baro_MS5534A.h 2010-10-19 
20:54:52 UTC (rev 6186)
@@ -0,0 +1,61 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2007  ENAC
+ *
+ * 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. 
+ *
+ */
+
+/** \file baro_MS5534A.h
+ *  \brief Handling of the MS5534a pressure sensor
+ *
+ */
+
+#ifndef BARO_MS5534A_H
+#define BARO_MS5534A_H
+
+#include "std.h"
+
+#ifdef USE_BARO_MS5534A
+
+extern bool_t baro_MS5534A_do_reset;
+extern bool_t baro_MS5534A_available;
+extern uint32_t baro_MS5534A_pressure;
+extern uint16_t baro_MS5534A_temp;
+extern bool_t alt_baro_enabled;
+extern uint32_t baro_MS5534A_ground_pressure;
+extern float baro_MS5534A_r;
+extern float baro_MS5534A_sigma2;
+extern float baro_MS5534A_z;
+
+void baro_MS5534A_init(void);
+void baro_MS5534A_reset(void);
+
+/* To be called not faster than 30Hz */
+void baro_MS5534A_send(void);
+
+/* Set baro_MS5534A_available when pressure and temp are readable */
+void baro_MS5534A_event_task( void );
+
+void baro_MS5534A_event( void );
+
+#endif // USE_BARO_MS5534A
+
+#endif // BARO_MS5534A_H
+




reply via email to

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