From 4484a4232a61e2bb2f82e9fbc02dc99a51b39d40 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 14 Feb 2014 16:28:03 +0900 Subject: [PATCH] AC_Fence: fix example sketch --- .../examples/AC_Fence_test/AC_Fence_test.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AC_Fence/examples/AC_Fence_test/AC_Fence_test.pde b/libraries/AC_Fence/examples/AC_Fence_test/AC_Fence_test.pde index dc56989a15..73fcf510c4 100644 --- a/libraries/AC_Fence/examples/AC_Fence_test/AC_Fence_test.pde +++ b/libraries/AC_Fence/examples/AC_Fence_test/AC_Fence_test.pde @@ -22,7 +22,7 @@ #include #include #include // PID library -#include // PID library +#include // P library #include // ArduPilot general purpose FIFO buffer #include // Inertial Navigation library #include // Fence library @@ -52,10 +52,10 @@ AP_GPS_Auto auto_gps(&gps); GPS_Glitch gps_glitch(gps); AP_Compass_HMC5843 compass; -AP_AHRS_DCM ahrs(ins, gps); +AP_AHRS_DCM ahrs(ins, baro, gps); // Inertial Nav declaration -AP_InertialNav inertial_nav(&ahrs, &baro, gps, gps_glitch); +AP_InertialNav inertial_nav(ahrs, baro, gps, gps_glitch); // Fence AC_Fence fence(&inertial_nav); @@ -67,9 +67,9 @@ void setup() void loop() { - // call update function - hal.console->printf_P(PSTR("hello")); - hal.scheduler->delay(1); + // print message to user + hal.console->printf_P(PSTR("this example tests compilation only")); + hal.scheduler->delay(5000); } AP_HAL_MAIN();