Skip to content

Commit

Permalink
SRV_Channel: expose public function to convert scaled value to pwm
Browse files Browse the repository at this point in the history
Allow other modules to get and store the PWM value for a specific scaled
value and re-apply it later.
  • Loading branch information
tpwrules authored and tridge committed Oct 16, 2023
1 parent 1ece48b commit 79b7852
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 10 deletions.
21 changes: 11 additions & 10 deletions libraries/SRV_Channel/SRV_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -201,6 +201,15 @@ uint16_t SRV_Channel::pwm_from_angle(float scaled_value) const
}
}

uint16_t SRV_Channel::pwm_from_scaled_value(float scaled_value) const
{
if (type_angle) {
return pwm_from_angle(scaled_value);
} else {
return pwm_from_range(scaled_value);
}
}

void SRV_Channel::calc_pwm(float output_scaled)
{
if (have_pwm_mask & (1U<<ch_num)) {
Expand All @@ -221,11 +230,7 @@ void SRV_Channel::calc_pwm(float output_scaled)
return;
}

if (type_angle) {
output_pwm = pwm_from_angle(output_scaled);
} else {
output_pwm = pwm_from_range(output_scaled);
}
output_pwm = pwm_from_scaled_value(output_scaled);
}

void SRV_Channel::set_output_pwm(uint16_t pwm, bool force)
Expand All @@ -240,11 +245,7 @@ void SRV_Channel::set_output_pwm(uint16_t pwm, bool force)
void SRV_Channel::set_output_norm(float value)
{
// convert normalised value to pwm
if (type_angle) {
set_output_pwm(pwm_from_angle(value * high_out));
} else {
set_output_pwm(pwm_from_range(value * high_out));
}
set_output_pwm(pwm_from_scaled_value(value * high_out));
}

// set angular range of scaled output
Expand Down
3 changes: 3 additions & 0 deletions libraries/SRV_Channel/SRV_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,9 @@ class SRV_Channel {
return function.configured();
}

// convert a scaled value (either range or angle depending on setup) to a pwm
uint16_t pwm_from_scaled_value(float scaled_value) const;

// specify that small rc input changes should be ignored during passthrough
// used by DO_SET_SERVO commands
void ignore_small_rcin_changes() { ign_small_rcin_changes = true; }
Expand Down

0 comments on commit 79b7852

Please sign in to comment.