From 5d84850f3202b8521cacd7b3162edc1fa0726b7b Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Apr 2018 19:18:15 -0700 Subject: [PATCH] AC_PID: Use RC_Channels instead of hal.rcin --- libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp index 15be11dc01..c812092369 100644 --- a/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp +++ b/libraries/AC_PID/examples/AC_PID_test/AC_PID_test.cpp @@ -6,6 +6,7 @@ #include #include #include +#include void setup(); void loop(); @@ -44,10 +45,11 @@ void loop() hal.console->printf("P %f I %f D %f imax %f\n", (double)pid.kP(), (double)pid.kI(), (double)pid.kD(), (double)pid.imax()); // capture radio trim - radio_trim = hal.rcin->read(0); + radio_trim = RC_Channels::get_radio_in(0); while (true) { - radio_in = hal.rcin->read(0); + RC_Channels::set_pwm_all(); // poll the radio for new values + radio_in = RC_Channels::get_radio_in(0); error = radio_in - radio_trim; pid.set_input_filter_all(error); control_P = pid.get_p();