Skip to content

Commit

Permalink
SRV_Channel: fix scaled passthrough of ranges
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored and tridge committed Nov 15, 2023
1 parent 9012809 commit 265f19b
Showing 1 changed file with 9 additions and 1 deletion.
10 changes: 9 additions & 1 deletion libraries/SRV_Channel/SRV_Channel_aux.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,15 @@ void SRV_Channel::output_ch(void)
int16_t radio_in = c->get_radio_in();
if (passthrough_mapped) {
if (rc().has_valid_input()) {
radio_in = pwm_from_angle(c->norm_input_dz() * 4500);
switch (c->get_type()) {
case RC_Channel::ControlType::ANGLE:
radio_in = pwm_from_angle(c->norm_input_dz() * 4500);
break;
case RC_Channel::ControlType::RANGE:
// convert RC normalised input from -1 to +1 range to 0 to +1 and output as range
radio_in = pwm_from_range((c->norm_input_ignore_trim() + 1.0) * 0.5 * 4500);
break;
}
} else {
// no valid input. If we are in radio
// failsafe then go to trim values (if
Expand Down

0 comments on commit 265f19b

Please sign in to comment.