diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index bee9ac5b29..1a5ce7862c 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -42,16 +42,11 @@ extern "C" { } #include -#include "APM_BMP085.h" +#include "AP_Baro_BMP085.h" #define BMP085_ADDRESS 0x77 //(0xEE >> 1) #define BMP085_EOC 30 // End of conversion pin PC7 -// Constructors //////////////////////////////////////////////////////////////// -//APM_BMP085_Class::APM_BMP085_Class() -//{ -//} - // the apm2 hardware needs to check the state of the // chip using a direct IO port // On APM2 prerelease hw, the data ready port is hooked up to PE7, which @@ -60,7 +55,7 @@ extern "C" { // Public Methods ////////////////////////////////////////////////////////////// -bool APM_BMP085_Class::Init(int initialiseWireLib, bool apm2_hardware) +bool AP_Baro_BMP085::Init(int initialiseWireLib, bool apm2_hardware) { byte buff[22]; int i = 0; @@ -114,7 +109,7 @@ bool APM_BMP085_Class::Init(int initialiseWireLib, bool apm2_hardware) /* // 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 APM_BMP085_Class::Read() +uint8_t AP_Baro_BMP085::Read() { uint8_t result = 0; @@ -149,7 +144,7 @@ uint8_t APM_BMP085_Class::Read() */ // 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 APM_BMP085_Class::Read() +uint8_t AP_Baro_BMP085::Read() { uint8_t result = 0; @@ -173,7 +168,7 @@ uint8_t APM_BMP085_Class::Read() // Send command to Read Pressure -void APM_BMP085_Class::Command_ReadPress() +void AP_Baro_BMP085::Command_ReadPress() { Wire.beginTransmission(BMP085_ADDRESS); Wire.send(0xF4); @@ -182,7 +177,7 @@ void APM_BMP085_Class::Command_ReadPress() } // Read Raw Pressure values -void APM_BMP085_Class::ReadPress() +void AP_Baro_BMP085::ReadPress() { byte msb; byte lsb; @@ -238,7 +233,7 @@ void APM_BMP085_Class::ReadPress() } // Send Command to Read Temperature -void APM_BMP085_Class::Command_ReadTemp() +void AP_Baro_BMP085::Command_ReadTemp() { Wire.beginTransmission(BMP085_ADDRESS); Wire.send(0xF4); @@ -247,7 +242,7 @@ void APM_BMP085_Class::Command_ReadTemp() } // Read Raw Temperature values -void APM_BMP085_Class::ReadTemp() +void AP_Baro_BMP085::ReadTemp() { byte tmp; Wire.beginTransmission(BMP085_ADDRESS); @@ -291,7 +286,7 @@ void APM_BMP085_Class::ReadTemp() } // Calculate Temperature and Pressure in real units. -void APM_BMP085_Class::Calculate() +void AP_Baro_BMP085::Calculate() { long x1, x2, x3, b3, b5, b6, p; unsigned long b4, b7; diff --git a/libraries/AP_Baro/AP_Baro_BMP085.h b/libraries/AP_Baro/AP_Baro_BMP085.h index 49de18cd76..6a1e0352d8 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.h +++ b/libraries/AP_Baro/AP_Baro_BMP085.h @@ -1,15 +1,15 @@ -#ifndef APM_BMP085_h -#define APM_BMP085_h +#ifndef __AP_BARO_BMP085_H__ +#define __AP_BARO_BMP085_H__ #define TEMP_FILTER_SIZE 4 #define PRESS_FILTER_SIZE 8 -#include "APM_BMP085_hil.h" +#include "AP_Baro.h" -class APM_BMP085_Class +class AP_Baro_BMP085 { public: - APM_BMP085_Class(): + AP_Baro_BMP085(): _temp_index(0), _press_index(0){}; // Constructor int32_t RawPress; @@ -46,4 +46,4 @@ class APM_BMP085_Class void Calculate(); }; -#endif +#endif // __AP_BARO_BMP085_H__ diff --git a/libraries/AP_Baro/AP_Baro_BMP085_hil.cpp b/libraries/AP_Baro/AP_Baro_BMP085_hil.cpp index 821e5e1b2e..181e807355 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085_hil.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085_hil.cpp @@ -1,5 +1,4 @@ - extern "C" { // AVR LibC Includes #include @@ -7,15 +6,15 @@ extern "C" { #include "WConstants.h" } -#include "APM_BMP085_hil.h" +#include "AP_Baro_BMP085_hil.h" // Constructors //////////////////////////////////////////////////////////////// -APM_BMP085_HIL_Class::APM_BMP085_HIL_Class() +AP_Baro_BMP085_HIL::AP_Baro_BMP085_HIL() { } // Public Methods ////////////////////////////////////////////////////////////// -void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool apm2_hardware) +void AP_Baro_BMP085_HIL::Init(int initialiseWireLib, bool apm2_hardware) { BMP085_State=1; } @@ -23,7 +22,7 @@ void APM_BMP085_HIL_Class::Init(int initialiseWireLib, bool apm2_hardware) // 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 APM_BMP085_HIL_Class::Read() +uint8_t AP_Baro_BMP085_HIL::Read() { uint8_t result = 0; @@ -42,7 +41,7 @@ uint8_t APM_BMP085_HIL_Class::Read() return(result); } -void APM_BMP085_HIL_Class::setHIL(float _Temp, float _Press) +void AP_Baro_BMP085_HIL::setHIL(float _Temp, float _Press) { // TODO: map floats to raw Temp = _Temp; diff --git a/libraries/AP_Baro/AP_Baro_BMP085_hil.h b/libraries/AP_Baro/AP_Baro_BMP085_hil.h index ac515e7b8a..57d3c948ec 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085_hil.h +++ b/libraries/AP_Baro/AP_Baro_BMP085_hil.h @@ -1,12 +1,15 @@ -#ifndef APM_BMP085_hil_h -#define APM_BMP085_hil_h -class APM_BMP085_HIL_Class +#ifndef __AP_BARO_BMP085_HIL_H__ +#define __AP_BARO_BMP085_HIL_H__ + +#include "AP_Baro.h" + +class AP_Baro_BMP085_HIL { private: uint8_t BMP085_State; public: - APM_BMP085_HIL_Class(); // Constructor + AP_Baro_BMP085_HIL(); // Constructor int32_t RawPress; int32_t RawTemp; int16_t Temp; @@ -19,4 +22,4 @@ class APM_BMP085_HIL_Class int32_t _offset_press; }; -#endif +#endif // __AP_BARO_BMP085_HIL_H__