mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scripting: added update_rpm() scripting binding
This commit is contained in:
parent
ec31a13275
commit
1995dbf47c
@ -1113,6 +1113,12 @@ function esc_telem:get_temperature(instance) end
|
||||
---@return number|nil
|
||||
function esc_telem:get_rpm(instance) end
|
||||
|
||||
-- update RPM for an ESC
|
||||
---@param param1 integer -- ESC number
|
||||
---@param param2 integer -- RPM
|
||||
---@param param3 number -- error rate
|
||||
function esc_telem:update_rpm(esc_index, rpm, error_rate) end
|
||||
|
||||
|
||||
-- desc
|
||||
---@class optical_flow
|
||||
|
@ -309,6 +309,7 @@ singleton AP_ESC_Telem method get_current boolean uint8_t 0 NUM_SERVO_CHANNELS f
|
||||
singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
||||
singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null
|
||||
singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null
|
||||
singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check
|
||||
|
||||
include AP_Param/AP_Param.h
|
||||
singleton AP_Param rename param
|
||||
|
Loading…
Reference in New Issue
Block a user