mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Baro: BMP085: use I2CDevice interface
This commit is contained in:
parent
3060c3da3c
commit
b05954660a
@ -295,10 +295,9 @@ void AP_Baro::init(void)
|
|||||||
drivers[0] = new AP_Baro_HIL(*this);
|
drivers[0] = new AP_Baro_HIL(*this);
|
||||||
_num_drivers = 1;
|
_num_drivers = 1;
|
||||||
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP085
|
#elif HAL_BARO_DEFAULT == HAL_BARO_BMP085
|
||||||
{
|
drivers[0] = new AP_Baro_BMP085(*this,
|
||||||
drivers[0] = new AP_Baro_BMP085(*this);
|
hal.i2c_mgr->get_device(HAL_BARO_BMP085_BUS, HAL_BARO_BMP085_I2C_ADDR));
|
||||||
_num_drivers = 1;
|
_num_drivers = 1;
|
||||||
}
|
|
||||||
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611 && HAL_BARO_MS5611_I2C_BUS == 0
|
#elif HAL_BARO_DEFAULT == HAL_BARO_MS5611 && HAL_BARO_MS5611_I2C_BUS == 0
|
||||||
{
|
{
|
||||||
drivers[0] = new AP_Baro_MS5611(*this, new AP_SerialBus_I2C(hal.i2c, HAL_BARO_MS5611_I2C_ADDR), false);
|
drivers[0] = new AP_Baro_MS5611(*this, new AP_SerialBus_I2C(hal.i2c, HAL_BARO_MS5611_I2C_ADDR), false);
|
||||||
|
@ -15,14 +15,13 @@
|
|||||||
*/
|
*/
|
||||||
#include "AP_Baro_BMP085.h"
|
#include "AP_Baro_BMP085.h"
|
||||||
|
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.h>
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
// 0xEE >> 1
|
|
||||||
#define BMP085_ADDRESS 0x77
|
|
||||||
|
|
||||||
#ifndef BMP085_EOC
|
#ifndef BMP085_EOC
|
||||||
#define BMP085_EOC -1
|
#define BMP085_EOC -1
|
||||||
#endif
|
#endif
|
||||||
@ -30,16 +29,17 @@ extern const AP_HAL::HAL &hal;
|
|||||||
// oversampling 3 gives 26ms conversion time. We then average
|
// oversampling 3 gives 26ms conversion time. We then average
|
||||||
#define OVERSAMPLING 3
|
#define OVERSAMPLING 3
|
||||||
|
|
||||||
AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro)
|
AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev)
|
||||||
: AP_Baro_Backend(baro)
|
: AP_Baro_Backend(baro)
|
||||||
|
, _dev(std::move(dev))
|
||||||
{
|
{
|
||||||
uint8_t buff[22];
|
uint8_t buff[22];
|
||||||
|
|
||||||
// get pointer to i2c bus semaphore
|
// get pointer to i2c bus semaphore
|
||||||
AP_HAL::Semaphore *i2c_sem = hal.i2c->get_semaphore();
|
AP_HAL::Semaphore *sem = _dev->get_semaphore();
|
||||||
|
|
||||||
// take i2c bus sempahore
|
// take i2c bus sempahore
|
||||||
if (!i2c_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
if (!sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
|
||||||
AP_HAL::panic("BMP085: unable to get semaphore");
|
AP_HAL::panic("BMP085: unable to get semaphore");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -49,7 +49,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// We read the calibration data registers
|
// We read the calibration data registers
|
||||||
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {
|
if (!_dev->read_registers(0xAA, buff, 22)) {
|
||||||
AP_HAL::panic("BMP085: bad calibration registers");
|
AP_HAL::panic("BMP085: bad calibration registers");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -75,7 +75,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro)
|
|||||||
|
|
||||||
BMP085_State = 0;
|
BMP085_State = 0;
|
||||||
|
|
||||||
i2c_sem->give();
|
sem->give();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -83,15 +83,14 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro)
|
|||||||
*/
|
*/
|
||||||
void AP_Baro_BMP085::accumulate(void)
|
void AP_Baro_BMP085::accumulate(void)
|
||||||
{
|
{
|
||||||
// get pointer to i2c bus semaphore
|
AP_HAL::Semaphore *sem = _dev->get_semaphore();
|
||||||
AP_HAL::Semaphore *i2c_sem = hal.i2c->get_semaphore();
|
|
||||||
|
|
||||||
if (!_data_ready()) {
|
if (!_data_ready()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// take i2c bus sempahore
|
// take i2c bus sempahore
|
||||||
if (!i2c_sem->take(1)) {
|
if (!sem->take(1)) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -109,7 +108,7 @@ void AP_Baro_BMP085::accumulate(void)
|
|||||||
_cmd_read_pressure();
|
_cmd_read_pressure();
|
||||||
}
|
}
|
||||||
|
|
||||||
i2c_sem->give();
|
sem->give();
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -138,8 +137,7 @@ void AP_Baro_BMP085::update(void)
|
|||||||
void AP_Baro_BMP085::_cmd_read_pressure()
|
void AP_Baro_BMP085::_cmd_read_pressure()
|
||||||
{
|
{
|
||||||
// Mode 0x34+(OVERSAMPLING << 6) is osrs=3 when OVERSAMPLING=3 => 25.5ms conversion time
|
// Mode 0x34+(OVERSAMPLING << 6) is osrs=3 when OVERSAMPLING=3 => 25.5ms conversion time
|
||||||
hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4,
|
_dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));
|
||||||
0x34 + (OVERSAMPLING << 6));
|
|
||||||
_last_press_read_command_time = AP_HAL::millis();
|
_last_press_read_command_time = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -148,9 +146,9 @@ bool AP_Baro_BMP085::_read_pressure()
|
|||||||
{
|
{
|
||||||
uint8_t buf[3];
|
uint8_t buf[3];
|
||||||
|
|
||||||
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xF6, 3, buf) != 0) {
|
if (!_dev->read_registers(0xF6, buf, 3)) {
|
||||||
_retry_time = AP_HAL::millis() + 1000;
|
_retry_time = AP_HAL::millis() + 1000;
|
||||||
hal.i2c->setHighSpeed(false);
|
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -163,7 +161,7 @@ bool AP_Baro_BMP085::_read_pressure()
|
|||||||
// Send Command to Read Temperature
|
// Send Command to Read Temperature
|
||||||
void AP_Baro_BMP085::_cmd_read_temp()
|
void AP_Baro_BMP085::_cmd_read_temp()
|
||||||
{
|
{
|
||||||
hal.i2c->writeRegister(BMP085_ADDRESS, 0xF4, 0x2E);
|
_dev->write_register(0xF4, 0x2E);
|
||||||
_last_temp_read_command_time = AP_HAL::millis();
|
_last_temp_read_command_time = AP_HAL::millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -173,8 +171,8 @@ void AP_Baro_BMP085::_read_temp()
|
|||||||
uint8_t buf[2];
|
uint8_t buf[2];
|
||||||
int32_t _temp_sensor;
|
int32_t _temp_sensor;
|
||||||
|
|
||||||
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xF6, 2, buf) != 0) {
|
if (!_dev->read_registers(0xF6, buf, 2)) {
|
||||||
hal.i2c->setHighSpeed(false);
|
_dev->set_speed(AP_HAL::Device::SPEED_LOW);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_temp_sensor = buf[0];
|
_temp_sensor = buf[0];
|
||||||
|
@ -1,13 +1,15 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include <AP_HAL/I2CDevice.h>
|
||||||
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
|
|
||||||
#include "AP_Baro_Backend.h"
|
#include "AP_Baro_Backend.h"
|
||||||
|
|
||||||
class AP_Baro_BMP085 : public AP_Baro_Backend
|
class AP_Baro_BMP085 : public AP_Baro_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// Constructor
|
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev);
|
||||||
AP_Baro_BMP085(AP_Baro &baro);
|
|
||||||
|
|
||||||
/* AP_Baro public interface: */
|
/* AP_Baro public interface: */
|
||||||
void update();
|
void update();
|
||||||
@ -21,6 +23,8 @@ private:
|
|||||||
void _calculate();
|
void _calculate();
|
||||||
bool _data_ready();
|
bool _data_ready();
|
||||||
|
|
||||||
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
|
||||||
|
|
||||||
uint8_t _instance;
|
uint8_t _instance;
|
||||||
float _temp_sum;
|
float _temp_sum;
|
||||||
float _press_sum;
|
float _press_sum;
|
||||||
|
@ -148,6 +148,8 @@
|
|||||||
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
|
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
|
||||||
#define HAL_INS_DEFAULT HAL_INS_FLYMAPLE
|
#define HAL_INS_DEFAULT HAL_INS_FLYMAPLE
|
||||||
#define HAL_BARO_DEFAULT HAL_BARO_BMP085
|
#define HAL_BARO_DEFAULT HAL_BARO_BMP085
|
||||||
|
#define HAL_BARO_BMP085_BUS 1
|
||||||
|
#define HAL_BARO_BMP085_I2C_ADDR 0x77
|
||||||
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HMC5843
|
||||||
#define HAL_SERIAL0_BAUD_DEFAULT 115200
|
#define HAL_SERIAL0_BAUD_DEFAULT 115200
|
||||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||||
|
Loading…
Reference in New Issue
Block a user