git-svn-id: https://arducopter.googlecode.com/svn/trunk@349 f9c3cf11-9bcb-44bc-f272-b75c42450872

This commit is contained in:
jasonshort 2010-08-30 00:15:54 +00:00
parent 2ca8ac7259
commit 5f459b1220
2 changed files with 8 additions and 9 deletions

2
libraries/GPS_IMU/GPS_IMU.cpp Normal file → Executable file
View File

@ -154,7 +154,7 @@ void GPS_IMU_Class::Read(void)
}// End for... }// End for...
} }
// If we don't receive GPS packets in 2 seconds => Bad FIX state // If we don't receive GPS packets in 2 seconds => Bad FIX state
if ((millis() - GPS_timer)>2000){ if ((millis() - GPS_timer) > 3000){
Fix = 0; Fix = 0;
} }
if (PrintErrors){ if (PrintErrors){

5
libraries/GPS_IMU/GPS_IMU.h Normal file → Executable file
View File

@ -23,7 +23,6 @@ class GPS_IMU_Class
uint8_t ck_b; uint8_t ck_b;
uint8_t IMU_ck_a; uint8_t IMU_ck_a;
uint8_t IMU_ck_b; uint8_t IMU_ck_b;
uint8_t IMU_step; uint8_t IMU_step;
uint8_t IMU_class; uint8_t IMU_class;
uint8_t message_num; uint8_t message_num;
@ -44,6 +43,7 @@ class GPS_IMU_Class
GPS_IMU_Class(); GPS_IMU_Class();
void Init(); void Init();
void Read(); void Read();
// Properties // Properties
long roll_sensor; // how much we're turning in deg * 100 long roll_sensor; // how much we're turning in deg * 100
long pitch_sensor; // our angle of attack in deg * 100 long pitch_sensor; // our angle of attack in deg * 100
@ -58,6 +58,7 @@ class GPS_IMU_Class
long Ground_Speed; long Ground_Speed;
long Ground_Course; long Ground_Course;
long Speed_3d; long Speed_3d;
uint8_t NumSats; // Number of visible satelites uint8_t NumSats; // Number of visible satelites
uint8_t Fix; // 1:GPS FIX 0:No FIX (normal logic) uint8_t Fix; // 1:GPS FIX 0:No FIX (normal logic)
uint8_t NewData; // 1:New GPS Data uint8_t NewData; // 1:New GPS Data
@ -65,5 +66,3 @@ class GPS_IMU_Class
}; };
extern GPS_IMU_Class GPS; extern GPS_IMU_Class GPS;
#endif