mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Adding reverse to Channel Raw output (unscaled output) to fix camera reversing.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@3297 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
3b622dc43c
commit
e05de48e2d
@ -80,7 +80,7 @@ RC_Channel::set_pwm(int pwm)
|
||||
if(radio_in == 0)
|
||||
radio_in = pwm;
|
||||
else
|
||||
radio_in = ((pwm + radio_in) >> 1); // Small filtering
|
||||
radio_in = (pwm + radio_in) >> 1; // Small filtering
|
||||
}else{
|
||||
radio_in = pwm;
|
||||
}
|
||||
@ -124,7 +124,7 @@ RC_Channel::calc_pwm(void)
|
||||
|
||||
}else if(_type == RC_CHANNEL_ANGLE_RAW){
|
||||
pwm_out = (float)servo_out * .1;
|
||||
radio_out = pwm_out + 1500;
|
||||
radio_out = (pwm_out * _reverse) + 1500;
|
||||
|
||||
}else{
|
||||
pwm_out = angle_to_pwm();
|
||||
|
Loading…
Reference in New Issue
Block a user