From 5f853768f4e3c8e87030973b05ae7d9963f29b0a Mon Sep 17 00:00:00 2001 From: "deweibel@gmail.com" Date: Mon, 28 Feb 2011 02:37:51 +0000 Subject: [PATCH] Add member/method to allow HIL to override radio values git-svn-id: https://arducopter.googlecode.com/svn/trunk@1732 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/APM_RC/APM_RC.cpp | 17 +++++++++++++++++ libraries/APM_RC/APM_RC.h | 4 ++++ 2 files changed, 21 insertions(+) diff --git a/libraries/APM_RC/APM_RC.cpp b/libraries/APM_RC/APM_RC.cpp index 5ff4e093b6..c62b68db77 100644 --- a/libraries/APM_RC/APM_RC.cpp +++ b/libraries/APM_RC/APM_RC.cpp @@ -150,6 +150,10 @@ uint16_t APM_RC_Class::InputCh(unsigned char ch) uint16_t result; uint16_t result2; + if (_HIL_override[ch] != 0) { + return _HIL_override[ch]; + } + // Because servo pulse variables are 16 bits and the interrupts are running values could be corrupted. // We dont want to stop interrupts to read radio channels so we have to do two readings to be sure that the value is correct... result = PWM_RAW[ch]>>1; // Because timer runs at 0.5us we need to do value/2 @@ -188,6 +192,19 @@ void APM_RC_Class::Force_Out6_Out7(void) TCNT3=39990; } +// allow HIL override of RC values +// A value of -1 means no change +// A value of 0 means no override, use the real RC values +void APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS]) +{ + for (unsigned char i=0; i