1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-01-18 03:52:11 +01:00

Get the pressure sensor working and reading into Revolution

This commit is contained in:
James Cotton 2011-11-27 00:36:01 -06:00
parent cd65df013e
commit 8bbc767a4e
9 changed files with 576 additions and 2 deletions

View File

@ -0,0 +1,174 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup AltitudeModule Altitude Module
* @brief Communicate with BMP085 and update @ref BaroAltitude "BaroAltitude UAV Object"
* @{
*
* @file altitude.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Altitude module, handles temperature and pressure readings from BMP085
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/**
* Output object: BaroAltitude
*
* This module will periodically update the value of the BaroAltitude object.
*
*/
#include "openpilot.h"
#include "altitude.h"
#include "baroaltitude.h" // object that will be updated by the module
#if defined(PIOS_INCLUDE_HCSR04)
#include "sonaraltitude.h" // object that will be updated by the module
#endif
// Private constants
#define STACK_SIZE_BYTES 500
#define TASK_PRIORITY (tskIDLE_PRIORITY+1)
//#define UPDATE_PERIOD 100
#define UPDATE_PERIOD 25
// Private types
// Private variables
static xTaskHandle taskHandle;
// down sampling variables
#define alt_ds_size 4
static int32_t alt_ds_temp = 0;
static int32_t alt_ds_pres = 0;
static int alt_ds_count = 0;
// Private functions
static void altitudeTask(void *parameters);
/**
* Initialise the module, called on startup
* \returns 0 on success or -1 if initialisation failed
*/
int32_t AltitudeStart()
{
BaroAltitudeInitialize();
#if defined(PIOS_INCLUDE_HCSR04)
SonarAltitudeInitialze();
#endif
// Start main task
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
return 0;
}
/**
* Initialise the module, called on startup
* \returns 0 on success or -1 if initialisation failed
*/
int32_t AltitudeInitialize()
{
// init down-sampling data
alt_ds_temp = 0;
alt_ds_pres = 0;
alt_ds_count = 0;
return 0;
}
MODULE_INITCALL(AltitudeInitialize, AltitudeStart)
/**
* Module thread, should not return.
*/
static void altitudeTask(void *parameters)
{
BaroAltitudeData data;
portTickType lastSysTime;
#if defined(PIOS_INCLUDE_HCSR04)
SonarAltitudeData sonardata;
int32_t value=0,timeout=5;
float coeff=0.25,height_out=0,height_in=0;
PIOS_HCSR04_Init();
PIOS_HCSR04_Trigger();
#endif
// TODO: Check the pressure sensor and set a warning if it fails test
// Main task loop
lastSysTime = xTaskGetTickCount();
while (1)
{
#if defined(PIOS_INCLUDE_HCSR04)
// Compute the current altitude (all pressures in kPa)
if(PIOS_HCSR04_Completed())
{
value = PIOS_HCSR04_Get();
if((value>100) && (value < 15000)) //from 3.4cm to 5.1m
{
height_in = value*0.00034;
height_out = (height_out * (1 - coeff)) + (height_in * coeff);
sonardata.Altitude = height_out; // m/us
}
// Update the AltitudeActual UAVObject
SonarAltitudeSet(&sonardata);
timeout=5;
PIOS_HCSR04_Trigger();
}
if(timeout--)
{
//retrigger
timeout=5;
PIOS_HCSR04_Trigger();
}
#endif
float temp, press;
// Update the temperature data
PIOS_MS5611_StartADC(TemperatureConv);
vTaskDelay(5);
PIOS_MS5611_ReadADC();
// Update the pressure data
PIOS_MS5611_StartADC(PressureConv);
vTaskDelay(5);
PIOS_MS5611_ReadADC();
temp = PIOS_MS5611_GetTemperature();
press = PIOS_MS5611_GetPressure();
data.Temperature = temp;
data.Pressure = press;
data.Altitude = 44330.0f * (1.0f - powf(data.Pressure / MS5611_P0, (1.0f / 5.255f)));
// Update the AltitudeActual UAVObject
BaroAltitudeSet(&data);
}
}
/**
* @}
* @}
*/

View File

@ -0,0 +1,41 @@
/**
******************************************************************************
* @addtogroup OpenPilotModules OpenPilot Modules
* @{
* @addtogroup AltitudeModule Altitude Module
* @brief Communicate with BMP085 and update @ref AltitudeActual "AltitudeActual UAV Object"
* @{
*
* @file altitude.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief Altitude module, reads temperature and pressure from BMP085
*
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef ALTITUDE_H
#define ALTITUDE_H
int32_t AltitudeInitialize();
#endif // ALTITUDE_H
/**
* @}
* @}
*/

View File

@ -0,0 +1,250 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_BMP085 BMP085 Functions
* @brief Hardware functions to deal with the altitude pressure sensor
* @{
*
* @file pios_ms5611.c
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief MS5611 Pressure Sensor Routines
* @see The GNU Public License (GPL) Version 3
*
******************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/* Project Includes */
// TODO: Clean this up. Getting around old constant.
#define PIOS_MS5611_OVERSAMPLING oversampling
#include "pios.h"
#if defined(PIOS_INCLUDE_MS5611)
/* Glocal Variables */
ConversionTypeTypeDef CurrentRead;
/* Local Variables */
MS5611CalibDataTypeDef CalibData;
/* Straight from the datasheet */
static int32_t X1, X2, X3, B3, B5, B6, P;
static uint32_t B4, B7;
static volatile int32_t RawTemperature;
static volatile int32_t RawPressure;
static volatile float Pressure;
static volatile float Temperature;
static int32_t PIOS_MS5611_Read(uint8_t address, uint8_t * buffer, uint8_t len);
static int32_t PIOS_MS5611_WriteCommand(uint8_t command);
// Move into proper driver structure with cfg stored
static uint32_t oversampling;
static const struct pios_ms5611_cfg * dev_cfg;
static int32_t i2c_id;
/**
* Initialise the BMP085 sensor
*/
int32_t ms5611_read_flag;
void PIOS_MS5611_Init(const struct pios_ms5611_cfg * cfg, int32_t i2c_device)
{
i2c_id = i2c_device;
oversampling = cfg->oversampling;
dev_cfg = cfg; // Store cfg before enabling interrupt
PIOS_MS5611_WriteCommand(MS5611_RESET);
PIOS_DELAY_WaitmS(20);
uint8_t data[2];
/* Calibration parameters */
for (int i = 0; i < 6; i++) {
PIOS_MS5611_Read(MS5611_CALIB_ADDR + i * 2, data, 2);
CalibData.C[i] = (data[0] << 8) | data[1];
}
}
/**
* Start the ADC conversion
* \param[in] PresOrTemp BMP085_PRES_ADDR or BMP085_TEMP_ADDR
* \return 0 for success, -1 for failure (conversion completed and not read)
*/
int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type)
{
/* Start the conversion */
if (Type == TemperatureConv) {
while (PIOS_MS5611_WriteCommand(MS5611_TEMP_ADDR) != 0)
continue;
} else if (Type == PressureConv) {
while (PIOS_MS5611_WriteCommand(MS5611_PRES_ADDR) != 0)
continue;
}
CurrentRead = Type;
return 0;
}
/**
* Read the ADC conversion value (once ADC conversion has completed)
* \param[in] PresOrTemp BMP085_PRES_ADDR or BMP085_TEMP_ADDR
* \return 0 if successfully read the ADC, -1 if failed
*/
int32_t PIOS_MS5611_ReadADC(void)
{
uint8_t Data[3];
Data[0] = 0;
Data[1] = 0;
Data[2] = 0;
static float dT;
/* Read and store the 16bit result */
if (CurrentRead == TemperatureConv) {
/* Read the temperature conversion */
if (PIOS_MS5611_Read(MS5611_ADC_READ, Data, 3) != 0)
return -1;
RawTemperature = (Data[0] << 16) | (Data[1] << 8) | Data[2];
dT = RawTemperature - CalibData.C[4] * (1 << 8);
Temperature = 2000 + dT * CalibData.C[5] / (1<<23);
Temperature /= 100.0f;
} else {
float Offset;
float Sens;
/* Read the pressure conversion */
if (PIOS_MS5611_Read(MS5611_ADC_READ, Data, 3) != 0)
return -1;
RawPressure = ((Data[0] << 16) | (Data[1] << 8) | Data[2]);
Offset = (float) CalibData.C[1] * (1<<16) +(float) CalibData.C[3] * (float) dT / (1<<7);
Sens = (float) CalibData.C[0] * (1<<15) + ((float) CalibData.C[2] * (float) dT) / (1<<8);
Pressure = (RawPressure * Sens / (1<<21) - Offset) / (1<<15);
Pressure /= 1000.0f;
}
return 0;
}
/**
* Return the most recently computed temperature in kPa
*/
float PIOS_MS5611_GetTemperature(void)
{
return Temperature;
}
/**
* Return the most recently computed pressure in kPa
*/
float PIOS_MS5611_GetPressure(void)
{
return Pressure;
}
/**
* Reads one or more bytes into a buffer
* \param[in] the command indicating the address to read
* \param[out] buffer destination buffer
* \param[in] len number of bytes which should be read
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
*/
int32_t PIOS_MS5611_Read(uint8_t address, uint8_t * buffer, uint8_t len)
{
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = MS5611_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = 1,
.buf = &address,
}
,
{
.info = __func__,
.addr = MS5611_I2C_ADDR,
.rw = PIOS_I2C_TXN_READ,
.len = len,
.buf = buffer,
}
};
return PIOS_I2C_Transfer(i2c_id, txn_list, NELEMENTS(txn_list));
}
/**
* Writes one or more bytes to the MS5611
* \param[in] address Register address
* \param[in] buffer source buffer
* \return 0 if operation was successful
* \return -1 if error during I2C transfer
*/
int32_t PIOS_MS5611_WriteCommand(uint8_t command)
{
const struct pios_i2c_txn txn_list[] = {
{
.info = __func__,
.addr = MS5611_I2C_ADDR,
.rw = PIOS_I2C_TXN_WRITE,
.len = 1,
.buf = &command,
}
,
};
return PIOS_I2C_Transfer(i2c_id, txn_list, NELEMENTS(txn_list));
}
/**
* @brief Run self-test operation.
* \return 0 if self-test succeed, -1 if failed
*/
int32_t PIOS_MS5611_Test()
{
// TODO: Is there a better way to test this than just checking that pressure/temperature has changed?
int32_t cur_value = 0;
cur_value = Temperature;
PIOS_MS5611_StartADC(TemperatureConv);
PIOS_DELAY_WaitmS(5);
PIOS_MS5611_ReadADC();
if (cur_value == Temperature)
return -1;
cur_value=Pressure;
PIOS_MS5611_StartADC(PressureConv);
PIOS_DELAY_WaitmS(26);
PIOS_MS5611_ReadADC();
if (cur_value == Pressure)
return -1;
return 0;
}
#endif
/**
* @}
* @}
*/

View File

@ -0,0 +1,74 @@
/**
******************************************************************************
* @addtogroup PIOS PIOS Core hardware abstraction layer
* @{
* @addtogroup PIOS_BMP085 BMP085 Functions
* @brief Hardware functions to deal with the altitude pressure sensor
* @{
*
* @file pios_ms5611.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
* @brief MS5611 functions header.
* @see The GNU Public License (GPL) Version 3
*
*****************************************************************************/
/*
* This program 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 3 of the License, or
* (at your option) any later version.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef PIOS_MS5611_H
#define PIOS_MS5611_H
#include <pios.h>
/* BMP085 Addresses */
#define MS5611_I2C_ADDR 0x77
#define MS5611_RESET 0x1E
#define MS5611_CALIB_ADDR 0xA2 /* First sample is factory stuff */
#define MS5611_CALIB_LEN 16
#define MS5611_ADC_READ 0x00
#define MS5611_PRES_ADDR 0x40
#define MS5611_TEMP_ADDR 0x50
#define MS5611_ADC_MSB 0xF6
#define MS5611_P0 101.3250f
/* Local Types */
typedef struct {
uint16_t C[6];
} MS5611CalibDataTypeDef;
typedef enum {
PressureConv,
TemperatureConv
} ConversionTypeTypeDef;
struct pios_ms5611_cfg {
uint32_t oversampling;
};
/* Public Functions */
extern void PIOS_MS5611_Init(const struct pios_ms5611_cfg * cfg, int32_t i2c_device);
extern int32_t PIOS_MS5611_StartADC(ConversionTypeTypeDef Type);
extern int32_t PIOS_MS5611_ReadADC(void);
extern float PIOS_MS5611_GetTemperature(void);
extern float PIOS_MS5611_GetPressure(void);
extern int32_t PIOS_MS5611_Test();
#endif /* PIOS_MS5611_H */
/**
* @}
* @}
*/

View File

@ -125,6 +125,9 @@
#if defined(PIOS_INCLUDE_MPU6000)
#include <pios_mpu6000.h>
#endif
#if defined(PIOS_INCLUDE_MS5611)
#include <pios_ms5611.h>
#endif
#include <pios_iap.h>
#if defined(PIOS_INCLUDE_ADXL345)

View File

@ -3338,10 +3338,13 @@
65FA9B8414709E9F0019A260 /* pios_tim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_tim.h; sourceTree = "<group>"; };
65FA9B8514709E9F0019A260 /* pios_usb_hid_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_usb_hid_priv.h; sourceTree = "<group>"; };
65FAA03F133B669400F6F5CD /* GTOP_BIN.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = GTOP_BIN.c; sourceTree = "<group>"; };
65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = receiveractivity.xml; sourceTree = "<group>"; };
65FAB8FC1480DA19000FF8B2 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_dsm.c; sourceTree = "<group>"; };
65FAB8FD1480DA19000FF8B2 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_pwm.c; sourceTree = "<group>"; };
65FAB8FE1481A5C5000FF8B2 /* pios_rtc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rtc.c; sourceTree = "<group>"; };
65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = receiveractivity.xml; sourceTree = "<group>"; };
65FAB9071481F9F6000FF8B2 /* pios_ms5611.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_ms5611.c; sourceTree = "<group>"; };
65FAB9091482072E000FF8B2 /* altitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = altitude.c; sourceTree = "<group>"; };
65FAB90B1482072E000FF8B2 /* altitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = altitude.h; sourceTree = "<group>"; };
65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = "<group>"; };
65FC66AA123F30F100B04F74 /* ahrs_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_timer.c; path = ../../AHRS/ahrs_timer.c; sourceTree = SOURCE_ROOT; };
65FC66AB123F312A00B04F74 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = "<group>"; };
@ -3476,6 +3479,7 @@
650D8E2812DFE16400D05CC9 /* Altitude */ = {
isa = PBXGroup;
children = (
65FAB9081482072E000FF8B2 /* revolution */,
650D8E2912DFE16400D05CC9 /* altitude.c */,
650D8E2A12DFE16400D05CC9 /* inc */,
);
@ -3886,6 +3890,7 @@
65904ED114613B6100FD9482 /* pios_led.c */,
6534B5581474F7B1003DF47C /* pios_mpu6000.c */,
65FA9B7A14709E700019A260 /* pios_mpu6050.c */,
65FAB9071481F9F6000FF8B2 /* pios_ms5611.c */,
65904ED214613B6100FD9482 /* pios_ppm.c */,
65FAB8FD1480DA19000FF8B2 /* pios_pwm.c */,
65FAB8FE1481A5C5000FF8B2 /* pios_rtc.c */,
@ -9218,6 +9223,24 @@
path = inc;
sourceTree = "<group>";
};
65FAB9081482072E000FF8B2 /* revolution */ = {
isa = PBXGroup;
children = (
65FAB9091482072E000FF8B2 /* altitude.c */,
65FAB90A1482072E000FF8B2 /* inc */,
);
name = revolution;
path = Revolution;
sourceTree = "<group>";
};
65FAB90A1482072E000FF8B2 /* inc */ = {
isa = PBXGroup;
children = (
65FAB90B1482072E000FF8B2 /* altitude.h */,
);
path = inc;
sourceTree = "<group>";
};
65FF4BB313791C3300146BE4 /* Bootloaders */ = {
isa = PBXGroup;
children = (

View File

@ -49,7 +49,7 @@ endif
FLASH_TOOL = OPENOCD
# List of modules to include
MODULES = Telemetry Attitude/revolution ManualControl Stabilization Actuator
MODULES = Telemetry Attitude/revolution ManualControl Stabilization Altitude/revolution Actuator
PYMODULES =
#FlightPlan

View File

@ -53,9 +53,11 @@
#define PIOS_INCLUDE_USART
//#define PIOS_INCLUDE_USB_HID
/* Select the sensors to include */
#define PIOS_INCLUDE_BMA180
#define PIOS_INCLUDE_HMC5883
#define PIOS_INCLUDE_MPU6000
#define PIOS_INCLUDE_MS5611
//#define PIOS_INCLUDE_HCSR04
#define PIOS_INCLUDE_COM

View File

@ -1426,6 +1426,11 @@ static const struct pios_hmc5883_cfg pios_hmc5883_cfg = {
};
#include "pios_ms5611.h"
static const struct pios_ms5611_cfg pios_ms5611_cfg = {
.oversampling = 1,
};
#include "pios_bma180.h"
static const struct pios_bma180_cfg pios_bma180_cfg = {
.drdy = {
@ -1660,6 +1665,8 @@ void PIOS_Board_Init(void) {
PIOS_BMA180_Init(&pios_bma180_cfg);
PIOS_HMC5883_Init(&pios_hmc5883_cfg);
PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id);
}
/**