mirror of https://github.com/ArduPilot/ardupilot
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
This commit is contained in:
parent
9b96d44343
commit
5f853768f4
|
@ -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<NUM_CHANNELS; i++) {
|
||||
if (v[i] != -1) {
|
||||
_HIL_override[i] = v[i];
|
||||
}
|
||||
}
|
||||
radio_status = 1;
|
||||
}
|
||||
|
||||
// make one instance for the user to use
|
||||
APM_RC_Class APM_RC;
|
||||
|
||||
|
|
|
@ -19,6 +19,10 @@ class APM_RC_Class
|
|||
void Force_Out0_Out1(void);
|
||||
void Force_Out2_Out3(void);
|
||||
void Force_Out6_Out7(void);
|
||||
void setHIL(int16_t v[NUM_CHANNELS]);
|
||||
|
||||
private:
|
||||
int16_t _HIL_override[NUM_CHANNELS];
|
||||
};
|
||||
|
||||
extern APM_RC_Class APM_RC;
|
||||
|
|
Loading…
Reference in New Issue