mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
removed scaling on control in because it might cause rounding issues.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2969 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
e32f8057bb
commit
e63fc0fe68
@ -89,15 +89,15 @@ RC_Channel::set_pwm(int pwm)
|
|||||||
//Serial.print("range ");
|
//Serial.print("range ");
|
||||||
control_in = pwm_to_range();
|
control_in = pwm_to_range();
|
||||||
control_in = (control_in < dead_zone) ? 0 : control_in;
|
control_in = (control_in < dead_zone) ? 0 : control_in;
|
||||||
if (fabs(scale_output) > 0){
|
//if (fabs(scale_output) > 0){
|
||||||
control_in *= scale_output;
|
// control_in *= scale_output;
|
||||||
}
|
//}
|
||||||
}else{
|
}else{
|
||||||
control_in = pwm_to_angle();
|
control_in = pwm_to_angle();
|
||||||
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
control_in = (abs(control_in) < dead_zone) ? 0 : control_in;
|
||||||
if (fabs(scale_output) > 0){
|
//if (fabs(scale_output) > 0){
|
||||||
control_in *= scale_output;
|
// control_in *= scale_output;
|
||||||
}
|
//}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user