SRV_Channel: added get_output_pwm_chan() for scripting

allows for servo drivers to be written in lua
This commit is contained in:
Andrew Tridgell 2024-11-19 13:55:14 +11:00
parent 2f9ff3ef73
commit d6b38f4009
2 changed files with 13 additions and 0 deletions

View File

@ -373,6 +373,9 @@ public:
// set output value for a specific function channel as a pwm value
static void set_output_pwm_chan(uint8_t chan, uint16_t value);
// get output value for a specific channel as a pwm value
static bool get_output_pwm_chan(uint8_t chan, uint16_t &value);
// set output value for a specific function channel as a pwm value for specified override time in ms
static void set_output_pwm_chan_timeout(uint8_t chan, uint16_t value, uint16_t timeout_ms);

View File

@ -434,6 +434,16 @@ void SRV_Channels::set_output_pwm_chan(uint8_t chan, uint16_t value)
}
}
// get output value for a specific channel as a pwm value
bool SRV_Channels::get_output_pwm_chan(uint8_t chan, uint16_t &value)
{
if (chan >= NUM_SERVO_CHANNELS) {
return false;
}
value = channels[chan].get_output_pwm();
return true;
}
#if AP_SCRIPTING_ENABLED && AP_SCHEDULER_ENABLED
// set output value for a specific function channel as a pwm value with loop based timeout
// timeout_ms of zero will clear override of the channel