mirror of https://github.com/ArduPilot/ardupilot
Change setHIL to return a bool based on if GCS joystick control is active
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2423 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
a42a939cc9
commit
4bce9465a6
|
@ -195,12 +195,21 @@ void APM_RC_Class::Force_Out6_Out7(void)
|
|||
// 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])
|
||||
bool APM_RC_Class::setHIL(int16_t v[NUM_CHANNELS])
|
||||
{
|
||||
uint8_t sum = 0;
|
||||
for (unsigned char i=0; i<NUM_CHANNELS; i++) {
|
||||
if (v[i] != -1) {
|
||||
_HIL_override[i] = v[i];
|
||||
}
|
||||
if (_HIL_override[i] != 0) {
|
||||
sum++;
|
||||
}
|
||||
if (sum == 0) {
|
||||
return 0;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
radio_status = 1;
|
||||
}
|
||||
|
|
|
@ -19,7 +19,7 @@ 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]);
|
||||
bool setHIL(int16_t v[NUM_CHANNELS]);
|
||||
|
||||
private:
|
||||
int16_t _HIL_override[NUM_CHANNELS];
|
||||
|
|
Loading…
Reference in New Issue