mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: remove recompute_pwm_no_deadzone
This commit is contained in:
parent
81fc725435
commit
e28650c8bd
|
@ -154,19 +154,6 @@ bool RC_Channel::update(void)
|
|||
return true;
|
||||
}
|
||||
|
||||
// recompute control values with no deadzone
|
||||
// When done this way the control_in value can be used as servo_out
|
||||
// to give the same output as input
|
||||
void RC_Channel::recompute_pwm_no_deadzone()
|
||||
{
|
||||
if (type_in == RC_CHANNEL_TYPE_RANGE) {
|
||||
control_in = pwm_to_range_dz(0);
|
||||
} else {
|
||||
//RC_CHANNEL_ANGLE
|
||||
control_in = pwm_to_angle_dz(0);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
return the center stick position expressed as a control_in value
|
||||
used for thr_mid in copter
|
||||
|
|
|
@ -35,7 +35,6 @@ public:
|
|||
|
||||
// read input from hal.rcin - create a control_in value
|
||||
bool update(void);
|
||||
void recompute_pwm_no_deadzone();
|
||||
|
||||
// calculate an angle given dead_zone and trim. This is used by the quadplane code
|
||||
// for hover throttle
|
||||
|
|
Loading…
Reference in New Issue