Sensor hil fix's

This commit is contained in:
Michael Oborne 2011-10-13 22:22:03 +08:00
parent c7c8c309be
commit 392160314e
9 changed files with 82 additions and 81 deletions

View File

@ -483,7 +483,7 @@ static void fast_loop()
#if HIL_MODE == HIL_MODE_SENSORS
// update hil before dcm update
hil.update();
gcs_update();
#endif
dcm.update_DCM();

View File

@ -1401,8 +1401,8 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// TODO: check scaling for temp/absPress
float temp = 70;
float absPress = 1;
// Serial.printf_P(PSTR("accel:\t%d\t%d\t%d\n"), packet.xacc, packet.yacc, packet.zacc);
// Serial.printf_P(PSTR("gyro:\t%d\t%d\t%d\n"), packet.xgyro, packet.ygyro, packet.zgyro);
Serial.printf_P(PSTR("accel: %d %d %d\n"), packet.xacc, packet.yacc, packet.zacc);
Serial.printf_P(PSTR("gyro: %d %d %d\n"), packet.xgyro, packet.ygyro, packet.zgyro);
// rad/sec
Vector3f gyros;

View File

@ -83,24 +83,6 @@
# define GPS_PROTOCOL GPS_PROTOCOL_NONE
#endif
// If we are in XPlane, diasble the mag
#if HIL_MODE != HIL_MODE_DISABLED // we are in HIL mode
// check xplane settings
#if HIL_PROTOCOL == HIL_PROTOCOL_XPLANE
// MAGNETOMETER not supported by XPLANE
# undef MAGNETOMETER
# define MAGNETOMETER DISABLED
# if HIL_MODE != HIL_MODE_ATTITUDE
# error HIL_PROTOCOL_XPLANE requires HIL_MODE_ATTITUDE
# endif
#endif
#endif
//////////////////////////////////////////////////////////////////////////////
// GPS_PROTOCOL
//

View File

@ -22,7 +22,7 @@ static void init_barometer(void)
for(int i = 0; i < 30; i++){ // We take some readings...
#if HIL_MODE == HIL_MODE_SENSORS
hil.update(); // look for inbound hil packets
gcs_update(); // look for inbound hil packets
#endif
barometer.Read(); // Get initial data from absolute pressure sensor

View File

@ -286,44 +286,4 @@ void APM_BMP085_Class::Calculate()
x1 = (x1 * 3038) >> 16;
x2 = (-7357 * p) >> 16;
Press = p + ((x1 + x2 + 3791) >> 4);
}
// Constructors ////////////////////////////////////////////////////////////////
APM_BMP085_HIL_Class::APM_BMP085_HIL_Class()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void APM_BMP085_HIL_Class::Init(int initialiseWireLib)
{
BMP085_State=1;
}
// 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 result = 0;
if (BMP085_State == 1){
BMP085_State++;
}else{
if (BMP085_State == 5){
BMP085_State = 1; // Start again from state = 1
result = 1; // New pressure reading
}else{
BMP085_State++;
result = 1; // New pressure reading
}
}
return(result);
}
void APM_BMP085_HIL_Class::setHIL(float _Temp, float _Press)
{
// TODO: map floats to raw
Temp = _Temp;
Press = _Press;
}
}

View File

@ -4,6 +4,8 @@
#define TEMP_FILTER_SIZE 16
#define PRESS_FILTER_SIZE 10
#include <APM_BMP085_hil.h>
class APM_BMP085_Class
{
public:
@ -43,21 +45,4 @@ class APM_BMP085_Class
void Calculate();
};
class APM_BMP085_HIL_Class
{
private:
uint8_t BMP085_State;
public:
int32_t RawPress;
int32_t RawTemp;
int16_t Temp;
int32_t Press;
//int Altitude;
uint8_t oss;
APM_BMP085_HIL_Class(); // Constructor
void Init(int initialiseWireLib = 1);
uint8_t Read();
void setHIL(float Temp, float Press);
};
#endif

View File

@ -0,0 +1,50 @@
extern "C" {
// AVR LibC Includes
#include <inttypes.h>
#include <avr/interrupt.h>
#include "WConstants.h"
}
#include "APM_BMP085_hil.h"
// Constructors ////////////////////////////////////////////////////////////////
APM_BMP085_HIL_Class::APM_BMP085_HIL_Class()
{
}
// Public Methods //////////////////////////////////////////////////////////////
void APM_BMP085_HIL_Class::Init(int initialiseWireLib)
{
BMP085_State=1;
}
// 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 result = 0;
if (BMP085_State == 1){
BMP085_State++;
}else{
if (BMP085_State == 5){
BMP085_State = 1; // Start again from state = 1
result = 1; // New pressure reading
}else{
BMP085_State++;
result = 1; // New pressure reading
}
}
return(result);
}
void APM_BMP085_HIL_Class::setHIL(float _Temp, float _Press)
{
// TODO: map floats to raw
Temp = _Temp;
Press = _Press;
}

View File

@ -0,0 +1,24 @@
#ifndef APM_BMP085_hil_h
#define APM_BMP085_hil_h
#define TEMP_FILTER_SIZE 16
#define PRESS_FILTER_SIZE 10
class APM_BMP085_HIL_Class
{
private:
uint8_t BMP085_State;
public:
APM_BMP085_HIL_Class(); // Constructor
int32_t RawPress;
int32_t RawTemp;
int16_t Temp;
int32_t Press;
//int Altitude;
uint8_t oss;
void Init(int initialiseWireLib = 1);
uint8_t Read();
void setHIL(float Temp, float Press);
};
#endif

View File

@ -13,7 +13,7 @@ public:
/// @name IMU protocol
//@{
virtual void init(Start_style style, void (*callback)(unsigned long t)) {}
virtual void init(Start_style style = COLD_START, void (*callback)(unsigned long t) = delay) {};
virtual void init_accel(void (*callback)(unsigned long t) = delay) {};
virtual void init_gyro(void (*callback)(unsigned long t) = delay) {};
virtual bool update(void) {