mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: rename AP_Baro_BMP085_HIL to AP_Baro_HIL
there is nothing specific to the BMP085 in it
This commit is contained in:
parent
a09c53a3ea
commit
2d089174cd
|
@ -73,7 +73,7 @@ private:
|
|||
|
||||
#include "AP_Baro_MS5611.h"
|
||||
#include "AP_Baro_BMP085.h"
|
||||
#include "AP_Baro_BMP085_hil.h"
|
||||
#include "AP_Baro_HIL.h"
|
||||
#include "AP_Baro_PX4.h"
|
||||
|
||||
#endif // __AP_BARO_H__
|
||||
|
|
|
@ -1,15 +1,15 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#include <AP_Baro.h>
|
||||
#include "AP_Baro_BMP085_hil.h"
|
||||
#include "AP_Baro_HIL.h"
|
||||
#include <AP_HAL.h>
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// Constructors ////////////////////////////////////////////////////////////////
|
||||
AP_Baro_BMP085_HIL::AP_Baro_BMP085_HIL(){}
|
||||
AP_Baro_HIL::AP_Baro_HIL(){}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
bool AP_Baro_BMP085_HIL::init()
|
||||
bool AP_Baro_HIL::init()
|
||||
{
|
||||
BMP085_State=1;
|
||||
return true;
|
||||
|
@ -17,7 +17,7 @@ bool AP_Baro_BMP085_HIL::init()
|
|||
|
||||
// Read the sensor. This is a state machine
|
||||
// We read one time Temperature (state = 1) and then 4 times Pressure (states 2-5)
|
||||
uint8_t AP_Baro_BMP085_HIL::read()
|
||||
uint8_t AP_Baro_HIL::read()
|
||||
{
|
||||
uint8_t result = 0;
|
||||
|
||||
|
@ -34,7 +34,7 @@ uint8_t AP_Baro_BMP085_HIL::read()
|
|||
return result;
|
||||
}
|
||||
|
||||
void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
||||
void AP_Baro_HIL::setHIL(float _Temp, float _Press)
|
||||
{
|
||||
_count++;
|
||||
_pressure_sum += _Press;
|
||||
|
@ -52,18 +52,18 @@ void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press)
|
|||
_last_update = hal.scheduler->millis();
|
||||
}
|
||||
|
||||
float AP_Baro_BMP085_HIL::get_pressure() {
|
||||
float AP_Baro_HIL::get_pressure() {
|
||||
return Press;
|
||||
}
|
||||
|
||||
float AP_Baro_BMP085_HIL::get_temperature() {
|
||||
float AP_Baro_HIL::get_temperature() {
|
||||
return Temp;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_BMP085_HIL::get_raw_pressure() {
|
||||
int32_t AP_Baro_HIL::get_raw_pressure() {
|
||||
return Press;
|
||||
}
|
||||
|
||||
int32_t AP_Baro_BMP085_HIL::get_raw_temp() {
|
||||
int32_t AP_Baro_HIL::get_raw_temp() {
|
||||
return Temp;
|
||||
}
|
|
@ -1,11 +1,11 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#ifndef __AP_BARO_BMP085_HIL_H__
|
||||
#define __AP_BARO_BMP085_HIL_H__
|
||||
#ifndef __AP_BARO__HIL_H__
|
||||
#define __AP_BARO__HIL_H__
|
||||
|
||||
#include "AP_Baro.h"
|
||||
|
||||
class AP_Baro_BMP085_HIL : public AP_Baro
|
||||
class AP_Baro_HIL : public AP_Baro
|
||||
{
|
||||
private:
|
||||
uint8_t BMP085_State;
|
||||
|
@ -16,7 +16,7 @@ private:
|
|||
uint8_t _count;
|
||||
|
||||
public:
|
||||
AP_Baro_BMP085_HIL(); // Constructor
|
||||
AP_Baro_HIL(); // Constructor
|
||||
|
||||
bool init();
|
||||
uint8_t read();
|
||||
|
@ -27,4 +27,4 @@ public:
|
|||
void setHIL(float Temp, float Press);
|
||||
};
|
||||
|
||||
#endif // __AP_BARO_BMP085_HIL_H__
|
||||
#endif // __AP_BARO__HIL_H__
|
Loading…
Reference in New Issue