mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Baro: Chnages to flymaple port.
Flymaple has no EOC pin
This commit is contained in:
parent
c1d3bedb60
commit
e3c20f06ac
@ -49,7 +49,7 @@
|
|||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || defined(APM2_BETA_HARDWARE)
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE || defined(APM2_BETA_HARDWARE)
|
||||||
#include "AP_Baro_BMP085.h"
|
#include "AP_Baro_BMP085.h"
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
@ -63,6 +63,12 @@ extern const AP_HAL::HAL& hal;
|
|||||||
// is not available to the arduino digitalRead function.
|
// is not available to the arduino digitalRead function.
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
#define BMP_DATA_READY() (PINE&0x80)
|
#define BMP_DATA_READY() (PINE&0x80)
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
||||||
|
// No EOC connection from Baro on Flymaple
|
||||||
|
// Use times instead.
|
||||||
|
// Temp conversion time is 4.5ms
|
||||||
|
// Pressure conversion time is 25.5ms (for OVERSAMPLING=3)
|
||||||
|
#define BMP_DATA_READY() (BMP085_State == 0 ? hal.scheduler->millis() > (_last_temp_read_command_time + 5) : hal.scheduler->millis() > (_last_press_read_command_time + 26))
|
||||||
#else
|
#else
|
||||||
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
|
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
|
||||||
#endif
|
#endif
|
||||||
@ -95,6 +101,9 @@ bool AP_Baro_BMP085::init()
|
|||||||
mc = ((int16_t)buff[18] << 8) | buff[19];
|
mc = ((int16_t)buff[18] << 8) | buff[19];
|
||||||
md = ((int16_t)buff[20] << 8) | buff[21];
|
md = ((int16_t)buff[20] << 8) | buff[21];
|
||||||
|
|
||||||
|
_last_press_read_command_time = 0;
|
||||||
|
_last_temp_read_command_time = 0;
|
||||||
|
|
||||||
//Send a command to read Temp
|
//Send a command to read Temp
|
||||||
Command_ReadTemp();
|
Command_ReadTemp();
|
||||||
|
|
||||||
@ -165,8 +174,10 @@ float AP_Baro_BMP085::get_temperature() {
|
|||||||
// Send command to Read Pressure
|
// Send command to Read Pressure
|
||||||
void AP_Baro_BMP085::Command_ReadPress()
|
void AP_Baro_BMP085::Command_ReadPress()
|
||||||
{
|
{
|
||||||
|
// Mode 0x34+(OVERSAMPLING << 6) is osrs=3 when OVERSAMPLING=3 => 25.5ms conversion time
|
||||||
uint8_t res = hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4,
|
uint8_t res = hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4,
|
||||||
0x34+(OVERSAMPLING << 6));
|
0x34+(OVERSAMPLING << 6));
|
||||||
|
_last_press_read_command_time = hal.scheduler->millis();
|
||||||
if (res != 0) {
|
if (res != 0) {
|
||||||
healthy = false;
|
healthy = false;
|
||||||
}
|
}
|
||||||
@ -199,6 +210,7 @@ void AP_Baro_BMP085::Command_ReadTemp()
|
|||||||
if (hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4, 0x2E) != 0) {
|
if (hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4, 0x2E) != 0) {
|
||||||
healthy = false;
|
healthy = false;
|
||||||
}
|
}
|
||||||
|
_last_temp_read_command_time = hal.scheduler->millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read Raw Temperature values
|
// Read Raw Temperature values
|
||||||
|
@ -30,6 +30,10 @@ private:
|
|||||||
uint8_t _count;
|
uint8_t _count;
|
||||||
float Temp;
|
float Temp;
|
||||||
float Press;
|
float Press;
|
||||||
|
// Flymaple has no EOC pin, so use times instead
|
||||||
|
uint32_t _last_press_read_command_time;
|
||||||
|
uint32_t _last_temp_read_command_time;
|
||||||
|
|
||||||
|
|
||||||
// State machine
|
// State machine
|
||||||
uint8_t BMP085_State;
|
uint8_t BMP085_State;
|
||||||
|
Loading…
Reference in New Issue
Block a user