From 59a3087cb62c31cb51dbe241fbc2b61f841eb015 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sat, 27 Nov 2010 03:04:30 +0000 Subject: [PATCH] added control / nav mixing git-svn-id: https://arducopter.googlecode.com/svn/trunk@944 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- libraries/RC_Channel/RC_Channel.cpp | 6 ++++++ libraries/RC_Channel/RC_Channel.h | 4 +++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index bd06912e3b..656323d9df 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -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) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 74eb45d0ee..1ab3e22147 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -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;