mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
RC_Channel: Rework set_pwm_no_deadzone() to a recompute function
This commit is contained in:
parent
7b7f5e242b
commit
c8fdb90ab5
@ -122,14 +122,12 @@ RC_Channel::set_pwm(int16_t pwm)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// read input from APM_RC - create a control_in value, but use a
|
// recompute control values with no deadzone
|
||||||
// zero value for the dead zone. When done this way the control_in
|
// When done this way the control_in value can be used as servo_out
|
||||||
// value can be used as servo_out to give the same output as input
|
// to give the same output as input
|
||||||
void
|
void
|
||||||
RC_Channel::set_pwm_no_deadzone(int16_t pwm)
|
RC_Channel::recompute_pwm_no_deadzone()
|
||||||
{
|
{
|
||||||
radio_in = pwm;
|
|
||||||
|
|
||||||
if (type_in == RC_CHANNEL_TYPE_RANGE) {
|
if (type_in == RC_CHANNEL_TYPE_RANGE) {
|
||||||
control_in = pwm_to_range_dz(0);
|
control_in = pwm_to_range_dz(0);
|
||||||
} else {
|
} else {
|
||||||
|
@ -43,7 +43,7 @@ public:
|
|||||||
|
|
||||||
// read input from hal.rcin - create a control_in value
|
// read input from hal.rcin - create a control_in value
|
||||||
void set_pwm(int16_t pwm);
|
void set_pwm(int16_t pwm);
|
||||||
void set_pwm_no_deadzone(int16_t pwm);
|
void recompute_pwm_no_deadzone();
|
||||||
|
|
||||||
// calculate an angle given dead_zone and trim. This is used by the quadplane code
|
// calculate an angle given dead_zone and trim. This is used by the quadplane code
|
||||||
// for hover throttle
|
// for hover throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user