mirror of https://github.com/ArduPilot/ardupilot
SRV_Channel: add set_output_norm
This commit is contained in:
parent
00757fb77f
commit
9f197db93c
|
@ -137,6 +137,17 @@ void SRV_Channel::set_output_pwm(uint16_t pwm, bool force)
|
|||
}
|
||||
}
|
||||
|
||||
// set normalised output from -1 to 1, assuming 0 at mid point of servo_min/servo_max
|
||||
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 angular range of scaled output
|
||||
void SRV_Channel::set_angle(int16_t angle)
|
||||
{
|
||||
|
|
|
@ -174,6 +174,9 @@ public:
|
|||
// get the output value as a pwm value
|
||||
uint16_t get_output_pwm(void) const { return output_pwm; }
|
||||
|
||||
// set normalised output from -1 to 1, assuming 0 at mid point of servo_min/servo_max
|
||||
void set_output_norm(float value);
|
||||
|
||||
// set angular range of scaled output
|
||||
void set_angle(int16_t angle);
|
||||
|
||||
|
@ -341,6 +344,9 @@ public:
|
|||
// Value is taken from pwm value. Returns zero on error.
|
||||
static float get_output_norm(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
// set normalised output (-1 to 1 with 0 at mid point of servo_min/servo_max) for the given function
|
||||
static void set_output_norm(SRV_Channel::Aux_servo_function_t function, float value);
|
||||
|
||||
// get output channel mask for a function
|
||||
static uint16_t get_output_channel_mask(SRV_Channel::Aux_servo_function_t function);
|
||||
|
||||
|
|
|
@ -641,6 +641,20 @@ float SRV_Channels::get_output_norm(SRV_Channel::Aux_servo_function_t function)
|
|||
return channels[chan].get_output_norm();
|
||||
}
|
||||
|
||||
// set normalised output (-1 to 1 with 0 at mid point of servo_min/servo_max) for the given function
|
||||
void SRV_Channels::set_output_norm(SRV_Channel::Aux_servo_function_t function, float value)
|
||||
{
|
||||
if (!function_assigned(function)) {
|
||||
return;
|
||||
}
|
||||
for (uint8_t i=0; i<NUM_SERVO_CHANNELS; i++) {
|
||||
SRV_Channel &c = channels[i];
|
||||
if (c.function == function) {
|
||||
c.set_output_norm(value);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
limit slew rate for an output function to given rate in percent per
|
||||
second. This assumes output has not yet done to the hal
|
||||
|
|
Loading…
Reference in New Issue