mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Scripting: add binding for get_output_pwm
This commit is contained in:
parent
78858bbcdd
commit
a13ddc1096
@ -1,21 +0,0 @@
|
||||
-- Testing set_output_pwm_chan_timeout
|
||||
--
|
||||
-- This will set MAIN1 servo to 1700 pwm for 1 second,
|
||||
-- then assigned function behavior for 1 second, and then 1100 pwm for 1 second
|
||||
|
||||
local flipflop = true
|
||||
|
||||
function update()
|
||||
if flipflop then
|
||||
SRV_Channels:set_output_pwm_chan_timeout(0, 1700, 1000)
|
||||
gcs:send_text(6, "flip---")
|
||||
else
|
||||
SRV_Channels:set_output_pwm_chan_timeout(0, 1100, 1000)
|
||||
gcs:send_text(6, "---flop")
|
||||
end
|
||||
flipflop = not flipflop
|
||||
return update, 2000
|
||||
end
|
||||
|
||||
gcs:send_text(6, "servo_override.lua is running")
|
||||
return update, 1000
|
25
libraries/AP_Scripting/examples/servo_set_get.lua
Normal file
25
libraries/AP_Scripting/examples/servo_set_get.lua
Normal file
@ -0,0 +1,25 @@
|
||||
-- Testing set_output_pwm_chan_timeout and get_output_pwm
|
||||
--
|
||||
-- This will set MAIN1 servo to 1700 pwm for 1 second,
|
||||
-- then assigned function behavior for 1 second, and then 1100 pwm for 1 second
|
||||
|
||||
local flipflop = true
|
||||
local K_AILERON = 4
|
||||
local aileron_channel = SRV_Channels:find_channel(K_AILERON)
|
||||
|
||||
function update()
|
||||
if flipflop then
|
||||
SRV_Channels:set_output_pwm_chan_timeout(aileron_channel, 1700, 1000)
|
||||
gcs:send_text(6, "flip---")
|
||||
else
|
||||
SRV_Channels:set_output_pwm_chan_timeout(aileron_channel, 1100, 1000)
|
||||
gcs:send_text(6, "---flop")
|
||||
end
|
||||
flipflop = not flipflop
|
||||
output_pwm = SRV_Channels:get_output_pwm(K_AILERON)
|
||||
gcs:send_text(6, "Function "..K_AILERON..", channel "..aileron_channel..", output "..output_pwm)
|
||||
return update, 2000
|
||||
end
|
||||
|
||||
gcs:send_text(6, "servo_set_get.lua is running")
|
||||
return update, 1000
|
@ -173,6 +173,7 @@ singleton SRV_Channels method set_output_pwm void SRV_Channel::Aux_servo_functio
|
||||
singleton SRV_Channels method set_output_pwm_chan void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t 0 UINT16_MAX
|
||||
singleton SRV_Channels method set_output_pwm_chan_timeout void uint8_t 0 NUM_SERVO_CHANNELS-1 uint16_t 0 UINT16_MAX uint16_t 0 UINT16_MAX
|
||||
singleton SRV_Channels method set_output_scaled void SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 int16_t INT16_MIN INT16_MAX
|
||||
singleton SRV_Channels method get_output_pwm boolean SRV_Channel::Aux_servo_function_t'enum SRV_Channel::k_none SRV_Channel::k_nr_aux_servo_functions-1 uint16_t'Null
|
||||
|
||||
include RC_Channel/RC_Channel.h
|
||||
singleton RC_Channels alias rc
|
||||
|
Loading…
Reference in New Issue
Block a user