mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add GPIO inputs and exmaple
This commit is contained in:
parent
4315a69b9d
commit
8b278b52b3
|
@ -5,8 +5,8 @@
|
|||
-- load the analog pin, there are only 16 of these available
|
||||
-- some are used by the main AP code, ie battery monitors
|
||||
-- assign them like this in the init, not in the main loop
|
||||
local analog = hal.analog_pin()
|
||||
analog:set_pin(13) -- typically 13 is the battery input
|
||||
local analog_in = analog:channel()
|
||||
analog_in:set_pin(13) -- typically 13 is the battery input
|
||||
|
||||
-- load a input pwm pin
|
||||
local pwm_in = PWMSource()
|
||||
|
@ -23,23 +23,23 @@ if not pwm_in_fail:set_pin(55) then -- AUX 6
|
|||
gcs:send_text(0, "Failed to setup PWM in on pin 55")
|
||||
end
|
||||
|
||||
hal.pin_mode(51,1) -- set AUX 2 to output, hal.pin_mode(51,0) would be input
|
||||
gpio:pinMode(51,1) -- set AUX 2 to output, gpio:pinMode(51,0) would be input
|
||||
|
||||
function update()
|
||||
gcs:send_text(0, string.format("voltage: %0.2f, PWM: %i, input: ", analog:voltage_average(), pwm_in:get_pwm_us()) .. tostring(hal.read(51)))
|
||||
gcs:send_text(0, string.format("voltage: %0.2f, PWM: %i, input: ", analog_in:voltage_average(), pwm_in:get_pwm_us()) .. tostring(gpio:read(51)))
|
||||
|
||||
-- analog:voltage_average() the average voltage since the last call
|
||||
-- analog:voltage_latest() the latest voltage reading
|
||||
-- analog:voltage_average_ratiometric() the average ratiometric voltage (relative to the board 5v)
|
||||
-- analog_in:voltage_average() the average voltage since the last call
|
||||
-- analog_in:voltage_latest() the latest voltage reading
|
||||
-- analog_in:voltage_average_ratiometric() the average ratiometric voltage (relative to the board 5v)
|
||||
|
||||
-- pwm_in:get_pwm_us() the latest pwm value in us
|
||||
-- pwm_in:get_pwm_avg_us() the average pwm value in us since the last call
|
||||
|
||||
-- hal.read(pin)
|
||||
-- hal.write(pin, state)
|
||||
-- hal.toggle(pin)
|
||||
-- gpio:read(pin)
|
||||
-- gpio:write(pin, state)
|
||||
-- gpio:toggle(pin)
|
||||
|
||||
hal.toggle(51)
|
||||
gpio:toggle(51)
|
||||
|
||||
return update, 1000
|
||||
end
|
||||
|
|
|
@ -351,3 +351,13 @@ userdata AP_HAL::PWMSource method set_pin boolean uint8_t 0 UINT8_MAX "Scripting
|
|||
userdata AP_HAL::PWMSource method get_pwm_us uint16_t
|
||||
userdata AP_HAL::PWMSource method get_pwm_avg_us uint16_t
|
||||
|
||||
singleton hal.gpio alias gpio
|
||||
singleton hal.gpio literal
|
||||
singleton hal.gpio method read boolean uint8_t 0 UINT8_MAX
|
||||
singleton hal.gpio method write void uint8_t 0 UINT8_MAX uint8_t 0 1
|
||||
singleton hal.gpio method toggle void uint8_t 0 UINT8_MAX
|
||||
singleton hal.gpio method pinMode void uint8_t 0 UINT8_MAX uint8_t 0 1
|
||||
|
||||
singleton hal.analogin alias analog
|
||||
singleton hal.analogin literal
|
||||
singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal
|
||||
|
|
Loading…
Reference in New Issue