From c1c20217199708588aae3ccbae9962416f23d25d Mon Sep 17 00:00:00 2001 From: "deweibel@gmail.com" Date: Thu, 17 Feb 2011 21:36:56 +0000 Subject: [PATCH] Correct factoring issue for AP_GPS_IMU XPlane HIL interface. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1673 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/AP_GPS/AP_GPS_IMU.cpp | 9 ++++++++- libraries/AP_GPS/AP_GPS_IMU.h | 4 ++++ 2 files changed, 12 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_IMU.cpp b/libraries/AP_GPS/AP_GPS_IMU.cpp index cc9d0667cf..9cfa79226a 100644 --- a/libraries/AP_GPS/AP_GPS_IMU.cpp +++ b/libraries/AP_GPS/AP_GPS_IMU.cpp @@ -223,4 +223,11 @@ void AP_GPS_IMU::checksum(byte data) { ck_a += data; ck_b += ck_a; -} \ No newline at end of file +} + + +/**************************************************************** + * Unused + ****************************************************************/ +void AP_GPS_IMU::setHIL(long time, float latitude, float longitude, float altitude, + float ground_speed, float ground_course, float speed_3d, uint8_t num_sats) {}; \ No newline at end of file diff --git a/libraries/AP_GPS/AP_GPS_IMU.h b/libraries/AP_GPS/AP_GPS_IMU.h index 5d4718da95..dd74463a19 100644 --- a/libraries/AP_GPS/AP_GPS_IMU.h +++ b/libraries/AP_GPS/AP_GPS_IMU.h @@ -20,6 +20,10 @@ class AP_GPS_IMU : public GPS { int airspeed; float imu_health; uint8_t imu_ok; + + // Unused + virtual void setHIL(long time, float latitude, float longitude, float altitude, + float ground_speed, float ground_course, float speed_3d, uint8_t num_sats); private: // Packet checksums