added control / nav mixing

git-svn-id: https://arducopter.googlecode.com/svn/trunk@944 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-11-27 03:04:30 +00:00
parent 0fd1228e27
commit 59a3087cb6
2 changed files with 9 additions and 1 deletions

View File

@ -63,6 +63,12 @@ RC_Channel::set_pwm(int pwm)
}
}
int
RC_Channel::control_mix(float value)
{
return (1 - abs(control_in / _high)) * value + control_in;
}
// are we below a threshold?
boolean
RC_Channel::get_failsafe(void)

View File

@ -42,7 +42,9 @@ class RC_Channel
// value generated from PWM
int16_t control_in;
int8_t dead_zone; // used to keep noise down and create a dead zone.
int control_mix(float value);
// current values to the servos - degrees * 100 (approx assuming servo is -45 to 45 degrees except [3] is 0 to 100
int16_t servo_out;