[Top][All Lists]
[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]
[paparazzi-commits] [6161] And more sensors!
From: |
Martin Mueller |
Subject: |
[paparazzi-commits] [6161] And more sensors! |
Date: |
Sun, 17 Oct 2010 00:10:51 +0000 |
Revision: 6161
http://svn.sv.gnu.org/viewvc/?view=rev&root=paparazzi&revision=6161
Author: mmm
Date: 2010-10-17 00:10:51 +0000 (Sun, 17 Oct 2010)
Log Message:
-----------
And more sensors!
Modified Paths:
--------------
paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml
paparazzi3/trunk/conf/messages.xml
paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.c
paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.h
paparazzi3/trunk/sw/airborne/modules/meteo/ir_mlx.c
paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.c
paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.h
Added Paths:
-----------
paparazzi3/trunk/conf/modules/baro_bmp.xml
paparazzi3/trunk/conf/modules/humid_hih.xml
paparazzi3/trunk/conf/modules/light_temt.xml
paparazzi3/trunk/conf/modules/temp_lm75.xml
paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.c
paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.h
paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.c
paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.h
paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.c
paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.h
paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.c
paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.h
Modified: paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml
===================================================================
--- paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml 2010-10-16
09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/conf/airframes/mm/fixed-wing/funjetmm.xml 2010-10-17
00:10:51 UTC (rev 6161)
@@ -55,8 +55,13 @@
<!-- modules -->
<modules>
+ <load name="baro_bmp.xml"/>
+ <load name="baro_scp_i2c.xml"/>
+ <!--load name="light_temt.xml"/>
+ <load name="humid_hih.xml"/>
+ <load name="temp_tmp102.xml"/>
+ <load name="temp_lm75.xml"/>
<load name="ir_mlx.xml"/>
- <!--load name="temp_tmp102.xml"/>
<load name="humid_dpicco.xml"/>
<load name="humid_sht.xml"/>
<load name="baro_scp_i2c.xml"/-->
Modified: paparazzi3/trunk/conf/messages.xml
===================================================================
--- paparazzi3/trunk/conf/messages.xml 2010-10-16 09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/conf/messages.xml 2010-10-17 00:10:51 UTC (rev 6161)
@@ -530,7 +530,10 @@
<field name="status" type="uint8"/>
</message>
- <!-- 84 is free -->
+ <message name="BMP_STATUS" id="84">
+ <field name="press" type="int32" unit="Pa"/>
+ <field name="temp" type="int32" unit="10x_deg_celsius"/>
+ </message>
<message name="MLX_STATUS" id="85">
<field name="itemp_case" type="uint16"/>
@@ -614,8 +617,17 @@
<field name="throttle" type="uint16"/>
</message>
- <!-- 96 is free -->
- <!-- 97 is free -->
+ <message name="HIH_STATUS" id="96">
+ <field name="humid" type="uint16"/>
+ <field name="fhumid" type="float" unit="rel_hum" format="%.2f"/>
+ <field name="ftemp" type="float" unit="deg_celsius" format="%.2f"/>
+ </message>
+
+ <message name="TEMT_STATUS" id="97">
+ <field name="light" type="uint16"/>
+ <field name="f_light" type="float" unit="percent" format="%.2f"/>
+ </message>
+
<!-- 98 is free -->
<!-- 99 is free -->
Added: paparazzi3/trunk/conf/modules/baro_bmp.xml
===================================================================
--- paparazzi3/trunk/conf/modules/baro_bmp.xml (rev 0)
+++ paparazzi3/trunk/conf/modules/baro_bmp.xml 2010-10-17 00:10:51 UTC (rev
6161)
@@ -0,0 +1,14 @@
+<!DOCTYPE module SYSTEM "module.dtd">
+
+<module name="baro_bmp" dir="meteo">
+ <header>
+ <file name="baro_bmp.h"/>
+ </header>
+ <init fun="baro_bmp_init()"/>
+ <periodic fun="baro_bmp_periodic()" freq="8"/>
+ <event fun="baro_bmp_event()"/>
+ <makefile target="ap">
+ <file name="baro_bmp.c"/>
+ </makefile>
+</module>
+
Added: paparazzi3/trunk/conf/modules/humid_hih.xml
===================================================================
--- paparazzi3/trunk/conf/modules/humid_hih.xml (rev 0)
+++ paparazzi3/trunk/conf/modules/humid_hih.xml 2010-10-17 00:10:51 UTC (rev
6161)
@@ -0,0 +1,15 @@
+<!DOCTYPE module SYSTEM "module.dtd">
+
+<module name="humid_hih" dir="meteo">
+ <header>
+ <file name="humid_hih.h"/>
+ </header>
+ <init fun="humid_hih_init()"/>
+ <periodic fun="humid_hih_periodic()" freq="4"/>
+ <makefile target="ap">
+ <file name="humid_hih.c"/>
+ <flag name="ADC_CHANNEL_HUMID_HIH" value="ADC_3"/>
+ <flag name="USE_ADC_3"/>
+ </makefile>
+</module>
+
Added: paparazzi3/trunk/conf/modules/light_temt.xml
===================================================================
--- paparazzi3/trunk/conf/modules/light_temt.xml
(rev 0)
+++ paparazzi3/trunk/conf/modules/light_temt.xml 2010-10-17 00:10:51 UTC
(rev 6161)
@@ -0,0 +1,15 @@
+<!DOCTYPE module SYSTEM "module.dtd">
+
+<module name="light_temt" dir="meteo">
+ <header>
+ <file name="light_temt.h"/>
+ </header>
+ <init fun="light_temt_init()"/>
+ <periodic fun="light_temt_periodic()" freq="4"/>
+ <makefile target="ap">
+ <file name="light_temt.c"/>
+ <flag name="ADC_CHANNEL_LIGHT_TEMT" value="ADC_4"/>
+ <flag name="USE_ADC_4"/>
+ </makefile>
+</module>
+
Added: paparazzi3/trunk/conf/modules/temp_lm75.xml
===================================================================
--- paparazzi3/trunk/conf/modules/temp_lm75.xml (rev 0)
+++ paparazzi3/trunk/conf/modules/temp_lm75.xml 2010-10-17 00:10:51 UTC (rev
6161)
@@ -0,0 +1,14 @@
+<!DOCTYPE module SYSTEM "module.dtd">
+
+<module name="temp_lm75" dir="meteo">
+ <header>
+ <file name="temp_lm75.h"/>
+ </header>
+ <init fun="lm75_init()"/>
+ <periodic fun="lm75_periodic()" freq="3"/>
+ <event fun="lm75_event()"/>
+ <makefile target="ap">
+ <file name="temp_lm75.c"/>
+ </makefile>
+</module>
+
Added: paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.c
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,164 @@
+/*
+ * $Id: baro_bmp.c $
+ *
+ * Copyright (C) 2010 Martin Mueller
+ *
+ * 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_bmp.c
+ * \brief Bosch BMP085 I2C sensor interface
+ *
+ * This reads the values for pressure and temperature from the Bosch BMP085
sensor through I2C.
+ */
+
+
+#include "baro_bmp.h"
+
+#include "sys_time.h"
+#include "i2c.h"
+#include "led.h"
+#include "uart.h"
+#include "messages.h"
+#include "downlink.h"
+
+#ifndef BMP_I2C_DEV
+#define BMP_I2C_DEV i2c0
+#endif
+
+#define BMP085_SLAVE_ADDR 0xEE
+
+struct i2c_transaction bmp_trans;
+
+uint8_t baro_bmp_status;
+uint32_t baro_bmp_pressure;
+uint16_t baro_bmp_temperature;
+
+int16_t bmp_ac1, bmp_ac2, bmp_ac3;
+uint16_t bmp_ac4, bmp_ac5, bmp_ac6;
+int16_t bmp_b1, bmp_b2;
+int16_t bmp_mb, bmp_mc, bmp_md;
+int32_t bmp_up, bmp_ut;
+
+void baro_bmp_init( void ) {
+ baro_bmp_status = BARO_BMP_UNINIT;
+ /* read calibration values */
+ bmp_trans.buf[0] = BMP085_EEPROM_AC1;
+ I2CTransceive(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 1, 22);
+}
+
+void baro_bmp_periodic( void ) {
+ if (baro_bmp_status == BARO_BMP_IDLE) {
+ /* start temp measurement (once) */
+ bmp_trans.buf[0] = BMP085_CTRL_REG;
+ bmp_trans.buf[1] = BMP085_START_TEMP;
+ I2CTransmit(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 2);
+ baro_bmp_status = BARO_BMP_START_TEMP;
+ }
+ else if (baro_bmp_status == BARO_BMP_START_TEMP) {
+ /* read temp measurement */
+ bmp_trans.buf[0] = BMP085_DAT_MSB;
+ I2CTransceive(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 1, 2);
+ baro_bmp_status = BARO_BMP_READ_TEMP;
+ }
+ else if (baro_bmp_status == BARO_BMP_START_PRESS) {
+ /* read press measurement */
+ bmp_trans.buf[0] = BMP085_DAT_MSB;
+ I2CTransceive(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 1, 3);
+ baro_bmp_status = BARO_BMP_READ_PRESS;
+ }
+}
+
+void baro_bmp_event( void ) {
+
+ if (bmp_trans.status == I2CTransSuccess) {
+
+ if (baro_bmp_status == BARO_BMP_UNINIT) {
+ /* get calibration data */
+ bmp_ac1 = (bmp_trans.buf[0] << 8) | bmp_trans.buf[1];
+ bmp_ac2 = (bmp_trans.buf[2] << 8) | bmp_trans.buf[3];
+ bmp_ac3 = (bmp_trans.buf[4] << 8) | bmp_trans.buf[5];
+ bmp_ac4 = (bmp_trans.buf[6] << 8) | bmp_trans.buf[7];
+ bmp_ac5 = (bmp_trans.buf[8] << 8) | bmp_trans.buf[9];
+ bmp_ac6 = (bmp_trans.buf[10] << 8) | bmp_trans.buf[11];
+ bmp_b1 = (bmp_trans.buf[12] << 8) | bmp_trans.buf[13];
+ bmp_b2 = (bmp_trans.buf[14] << 8) | bmp_trans.buf[15];
+ bmp_mb = (bmp_trans.buf[16] << 8) | bmp_trans.buf[17];
+ bmp_mc = (bmp_trans.buf[18] << 8) | bmp_trans.buf[19];
+ bmp_md = (bmp_trans.buf[20] << 8) | bmp_trans.buf[21];
+ baro_bmp_status = BARO_BMP_IDLE;
+ }
+ else if (baro_bmp_status == BARO_BMP_READ_TEMP) {
+ /* get uncompensated temperature */
+ bmp_ut = (bmp_trans.buf[0] << 8) | bmp_trans.buf[1];
+ /* start high res pressure measurement */
+ bmp_trans.buf[0] = BMP085_CTRL_REG;
+ bmp_trans.buf[1] = BMP085_START_P3;
+ I2CTransmit(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 2);
+ baro_bmp_status = BARO_BMP_START_PRESS;
+ }
+ else if (baro_bmp_status == BARO_BMP_READ_PRESS) {
+ int32_t bmp_p, bmp_t;
+ int32_t bmp_x1, bmp_x2, bmp_x3;
+ int32_t bmp_b3, bmp_b5, bmp_b6;
+ uint32_t bmp_b4, bmp_b7;
+
+ /* get uncompensated pressure, oss=3 */
+ bmp_up = (bmp_trans.buf[0] << 11) |
+ (bmp_trans.buf[1] << 3) |
+ bmp_trans.buf[2];
+ /* start temp measurement */
+ bmp_trans.buf[0] = BMP085_CTRL_REG;
+ bmp_trans.buf[1] = BMP085_START_TEMP;
+ I2CTransmit(BMP_I2C_DEV, bmp_trans, BMP085_SLAVE_ADDR, 2);
+ baro_bmp_status = BARO_BMP_START_TEMP;
+
+ /* compensate temperature */
+ bmp_x1 = (bmp_ut - bmp_ac6) * bmp_ac5 / (1<<15);
+ bmp_x2 = bmp_mc * (1<<11) / (bmp_x1 + bmp_md);
+ bmp_b5 = bmp_x1 + bmp_x2;
+ bmp_t = (bmp_b5 + 8) / (1<<4);
+
+ /* compensate pressure */
+ bmp_b6 = bmp_b5 - 4000;
+ bmp_x1 = (bmp_b2 * (bmp_b6 * bmp_b6 / (1<<12))) / (1<<11);
+ bmp_x2 = bmp_ac2 *bmp_b6 / (1<<11);
+ bmp_x3 = bmp_x1 + bmp_x2;
+ bmp_b3 = (((bmp_ac1 * 4 + bmp_x3) << 3) + 2) / 4;
+ bmp_x1 = bmp_ac3 * bmp_b6 / (1<<13);
+ bmp_x2 = (bmp_b1 * (bmp_b6 * bmp_b6 / (1<<12))) / (1<<16);
+ bmp_x3 = ((bmp_x1 + bmp_x2) +2) / (1<<2);
+ bmp_b4 = bmp_ac4 * (uint32_t)(bmp_x3 + 32768) / (1<<15);
+ bmp_b7 = ((uint32_t)bmp_up - bmp_b3) * (50000>>3);
+ if (bmp_b7 < 0x80000000)
+ bmp_p = (bmp_b7 * 2) / bmp_b4;
+ else
+ bmp_p = (bmp_b7 * bmp_b4) * 2;
+ bmp_x1 = (bmp_p / (1<<8)) * (bmp_p / (1<<8));
+ bmp_x1 = (bmp_x1 * 3038) / (1<<16);
+ bmp_x2 = (-7357 * bmp_p) / (1<<16);
+ bmp_p = bmp_p + (bmp_x1 + bmp_x2 + 3791) / (1<<4);
+
+ baro_bmp_temperature = bmp_t;
+ baro_bmp_pressure = bmp_p;
+ DOWNLINK_SEND_BMP_STATUS(DefaultChannel, &bmp_p, &bmp_t);
+ }
+ }
+}
+
Added: paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.h
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/baro_bmp.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,45 @@
+#ifndef BARO_BMP_H
+#define BARO_BMP_H
+
+#include "std.h"
+
+#define BMP085_EEPROM_AC1 0xAA
+#define BMP085_EEPROM_AC2 0xAC
+#define BMP085_EEPROM_AC3 0xAE
+#define BMP085_EEPROM_AC4 0xB0
+#define BMP085_EEPROM_AC5 0xB2
+#define BMP085_EEPROM_AC6 0xB4
+#define BMP085_EEPROM_B1 0xB6
+#define BMP085_EEPROM_B2 0xB8
+#define BMP085_EEPROM_MB 0xBA
+#define BMP085_EEPROM_MC 0xBC
+#define BMP085_EEPROM_MD 0xBE
+
+#define BMP085_CTRL_REG 0xF4
+
+#define BMP085_START_TEMP 0x2E
+#define BMP085_START_P0 0x34
+#define BMP085_START_P1 0x74
+#define BMP085_START_P2 0xB4
+#define BMP085_START_P3 0xF4
+
+#define BMP085_DAT_MSB 0xF6
+#define BMP085_DAT_LSB 0xF7
+#define BMP085_DAT_XLSB 0xF8
+
+#define BARO_BMP_UNINIT 0
+#define BARO_BMP_IDLE 1
+#define BARO_BMP_START_TEMP 2
+#define BARO_BMP_READ_TEMP 3
+#define BARO_BMP_START_PRESS 4
+#define BARO_BMP_READ_PRESS 5
+
+extern uint8_t baro_bmp_status;
+extern uint32_t baro_bmp_pressure;
+extern uint16_t baro_bmp_temperature;
+
+void baro_bmp_init(void);
+void baro_bmp_periodic(void);
+void baro_bmp_event(void);
+
+#endif
Modified: paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.c 2010-10-16
09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -28,9 +28,9 @@
#define SCP1000_SLAVE_ADDR 0x22
static void baro_scp_start_high_res_measurement(void) {
- /* write 0x0A to 0x03 */
- scp_trans.buf[0] = 0x03;
- scp_trans.buf[1] = 0x0A;
+ /* switch to high resolution */
+ scp_trans.buf[0] = SCP1000_OPERATION;
+ scp_trans.buf[1] = SCP1000_HIGH_RES;
I2CTransmit(SCP_I2C_DEV, scp_trans, SCP1000_SLAVE_ADDR, 2);
}
@@ -47,7 +47,7 @@
} else if (baro_scp_status == BARO_SCP_IDLE) {
/* init: start two byte temperature */
- scp_trans.buf[0] = 0x81;
+ scp_trans.buf[0] = SCP1000_TEMPOUT;
baro_scp_status = BARO_SCP_RD_TEMP;
I2CTransceive(SCP_I2C_DEV, scp_trans, SCP1000_SLAVE_ADDR, 1, 2);
}
@@ -68,7 +68,7 @@
baro_scp_temperature *= 5;
/* start one byte msb pressure */
- scp_trans.buf[0] = 0x7F;
+ scp_trans.buf[0] = SCP1000_DATARD8;
baro_scp_status = BARO_SCP_RD_PRESS_0;
I2CTransceive(SCP_I2C_DEV, scp_trans, SCP1000_SLAVE_ADDR, 1, 1);
}
@@ -79,7 +79,7 @@
baro_scp_pressure = scp_trans.buf[0] << 16;
/* start two byte lsb pressure */
- scp_trans.buf[0] = 0x80;
+ scp_trans.buf[0] = SCP1000_DATARD16;
baro_scp_status = BARO_SCP_RD_PRESS_1;
I2CTransceive(SCP_I2C_DEV, scp_trans, SCP1000_SLAVE_ADDR, 1, 2);
}
Modified: paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.h 2010-10-16
09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/baro_scp_i2c.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -3,6 +3,17 @@
#include "std.h"
+#define SCP1000_OPERATION 0x03
+
+#define SCP1000_HIGH_SPEED 0x09
+#define SCP1000_HIGH_RES 0x0A
+#define SCP1000_ULT_LOW_PW 0x0B
+#define SCP1000_LOW_PW 0x0C
+
+#define SCP1000_DATARD8 0x7F
+#define SCP1000_DATARD16 0x80
+#define SCP1000_TEMPOUT 0x81
+
#define BARO_SCP_UNINIT 0
#define BARO_SCP_IDLE 1
#define BARO_SCP_RD_TEMP 2
Added: paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.c
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,72 @@
+/*
+ * $Id: humid_hih.c $
+ *
+ * Copyright (C) 2010 Martin Mueller
+ *
+ * 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 humid_hih.c
+ * \brief Honeywell HIH-4030 sensor interface
+ *
+ * This reads the values for humidity from the Honeywell HIH-4030 sensor.
+ */
+
+
+#include "humid_hih.h"
+#include "temp_tmp102.h"
+#include "adc.h"
+#include "uart.h"
+#include "messages.h"
+#include "downlink.h"
+
+#ifndef ADC_CHANNEL_HUMID_HIH
+#define ADC_CHANNEL_HUMID_HIH ADC_3
+#endif
+
+#ifndef ADC_CHANNEL_HUMID_NB_SAMPLES
+#define ADC_CHANNEL_HUMID_NB_SAMPLES 16
+#endif
+
+uint16_t adc_humid_hih;
+float fhih_humid;
+
+static struct adc_buf buf_humid_hih;
+
+void humid_hih_init( void ) {
+ adc_buf_channel(ADC_CHANNEL_HUMID_HIH, &buf_humid_hih,
ADC_CHANNEL_HUMID_NB_SAMPLES);
+}
+
+void humid_hih_periodic( void ) {
+ float fvout;
+
+ adc_humid_hih = buf_humid_hih.sum / buf_humid_hih.av_nb_sample;
+
+ /* 36k/68k voltage divider, 3.3V full sweep, 10 bits adc */
+ fvout = (adc_humid_hih / 1024.) * 3.3 * (104./68.);
+
+ /* 5V supply, 1st order curve fit */
+ fhih_humid = ((fvout / 5.0)-0.16)/0.0062;
+
+ /* temperature compensation */
+ fhih_humid = fhih_humid/(1.0546 - (0.00216 * ftmp_temperature));
+
+ DOWNLINK_SEND_HIH_STATUS(DefaultChannel, &adc_humid_hih, &fhih_humid,
&ftmp_temperature);
+}
+
Added: paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.h
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/humid_hih.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,10 @@
+#ifndef HUMID_HIH_H
+#define HUMID_HIH_H
+
+#include <std.h>
+
+extern uint16_t adc_humid_hih;
+void humid_hih_init( void );
+void humid_hih_periodic( void );
+
+#endif
Modified: paparazzi3/trunk/sw/airborne/modules/meteo/ir_mlx.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/ir_mlx.c 2010-10-16 09:00:42 UTC
(rev 6160)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/ir_mlx.c 2010-10-17 00:10:51 UTC
(rev 6161)
@@ -51,7 +51,9 @@
float ir_mlx_temp_obj;
/* I2C address is set to 3 */
+#ifndef MLX90614_ADDR
#define MLX90614_ADDR 0x06
+#endif
// printf("Ta = %2.2f°C (0x%04X)\n", (tp*0.02)-273.15, tp);
Added: paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.c
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,64 @@
+/*
+ * $Id: light_temt.c $
+ *
+ * Copyright (C) 2010 Martin Mueller
+ *
+ * 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 light_temt.c
+ * \brief Vishay TEMT6000 ambient light sensor interface
+ *
+ * This reads the values for light intensity from the Vishay TEMT6000 sensor.
+ */
+
+
+#include "light_temt.h"
+#include "adc.h"
+#include "uart.h"
+#include "messages.h"
+#include "downlink.h"
+
+#ifndef ADC_CHANNEL_LIGHT_TEMT
+#define ADC_CHANNEL_LIGHT_TEMT ADC_4
+#endif
+
+#ifndef ADC_CHANNEL_LIGHT_NB_SAMPLES
+#define ADC_CHANNEL_LIGHT_NB_SAMPLES 16
+#endif
+
+uint16_t adc_light_temt;
+
+static struct adc_buf buf_light_temt;
+
+void light_temt_init( void ) {
+ adc_buf_channel(ADC_CHANNEL_LIGHT_TEMT, &buf_light_temt,
ADC_CHANNEL_LIGHT_NB_SAMPLES);
+}
+
+void light_temt_periodic( void ) {
+ float f_light_temt;
+
+ adc_light_temt = buf_light_temt.sum / buf_light_temt.av_nb_sample;
+
+ /* 3.6k/6.8k voltage divider, 10 bits adc */
+ f_light_temt = (adc_light_temt / 1024.) * 100.;
+
+ DOWNLINK_SEND_TEMT_STATUS(DefaultChannel, &adc_light_temt, &f_light_temt);
+}
+
Added: paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.h
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/light_temt.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,10 @@
+#ifndef LIGHT_TEMT_H
+#define LIGHT_TEMT_H
+
+#include <std.h>
+
+extern uint16_t adc_light_temt;
+void light_temt_init( void );
+void light_temt_periodic( void );
+
+#endif
Added: paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.c
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,80 @@
+/*
+ * $Id: temp_lm75.c $
+ *
+ * Copyright (C) 2010 Martin Mueller
+ *
+ * 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 temp_lm75.c
+ * \brief National LM75 I2C sensor interface
+ *
+ * This reads the values for temperature from the National LM75 sensor
through I2C.
+ */
+
+
+#include "temp_lm75.h"
+
+#include "i2c.h"
+#include "led.h"
+#include "uart.h"
+#include "messages.h"
+#include "downlink.h"
+
+uint8_t lm75_meas_started;
+struct i2c_transaction lm75_trans;
+
+#ifndef LM75_I2C_DEV
+#define LM75_I2C_DEV i2c0
+#endif
+
+/* address can be set through A0..A2, starting at 0x90 */
+
+#ifndef LM75_SLAVE_ADDR
+#define LM75_SLAVE_ADDR 0x90
+#endif
+
+void lm75_init(void) {
+ lm75_trans.status = I2CTransDone;
+}
+
+void lm75_periodic( void ) {
+ lm75_trans.buf[0] = LM75_TEMP_REG;
+ I2CTransceive(LM75_I2C_DEV, lm75_trans, LM75_SLAVE_ADDR, 1, 2);
+}
+
+void lm75_event( void ) {
+ if (lm75_trans.status == I2CTransSuccess) {
+ uint16_t lm75_temperature;
+ float flm75_temperature;
+
+ /* read two byte temperature */
+ lm75_temperature = lm75_trans.buf[0] << 8;
+ lm75_temperature |= lm75_trans.buf[1];
+ lm75_temperature >>= 7;
+ if (lm75_temperature & 0x0100)
+ lm75_temperature |= 0xFE00;
+
+ flm75_temperature = ((int16_t) lm75_temperature) / 2.;
+
+ DOWNLINK_SEND_TMP_STATUS(DefaultChannel, &lm75_temperature,
&flm75_temperature);
+ lm75_trans.status = I2CTransDone;
+ }
+}
+
Added: paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.h
(rev 0)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/temp_lm75.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -0,0 +1,17 @@
+#ifndef TEMP_LM75_H
+#define TEMP_LM75_H
+
+#include "std.h"
+
+#define LM75_TEMP_REG 0x00
+#define LM75_CONF_REG 0x01
+#define LM75_T_HYST_REG 0x02
+#define LM75_T_OS_REG 0x03
+#define LM75_PROD_REG 0x07
+
+
+void lm75_init(void);
+void lm75_periodic(void);
+void lm75_event(void);
+
+#endif
Modified: paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.c
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.c 2010-10-16
09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.c 2010-10-17
00:10:51 UTC (rev 6161)
@@ -38,6 +38,7 @@
#include "downlink.h"
uint8_t tmp_meas_started;
+float ftmp_temperature;
struct i2c_transaction tmp_trans;
#ifndef TMP_I2C_DEV
@@ -50,7 +51,9 @@
Addr: 0x90 0x92 0x94 0x96
*/
+#ifndef TMP102_SLAVE_ADDR
#define TMP102_SLAVE_ADDR 0x90
+#endif
/* OS=0 R1=1 R0=1 F1=0 POL=0 TM=0 SD=0 */
#define TMP102_CONF1 0x60
@@ -78,7 +81,6 @@
if ((tmp_trans.status == I2CTransSuccess) && (tmp_meas_started == TRUE)) {
uint16_t tmp_temperature;
- float ftmp_temperature;
/* read two byte temperature */
tmp_temperature = tmp_trans.buf[0] << 8;
Modified: paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.h
===================================================================
--- paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.h 2010-10-16
09:00:42 UTC (rev 6160)
+++ paparazzi3/trunk/sw/airborne/modules/meteo/temp_tmp102.h 2010-10-17
00:10:51 UTC (rev 6161)
@@ -8,6 +8,7 @@
#define TMP102_T_LOW_REG 0x02
#define TMP102_T_HIGH_REG 0x03
+extern float ftmp_temperature;
void tmp102_init(void);
void tmp102_periodic(void);
[Prev in Thread] |
Current Thread |
[Next in Thread] |
- [paparazzi-commits] [6161] And more sensors!,
Martin Mueller <=