mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: added set_rpm_scale API
This commit is contained in:
parent
3512ea792f
commit
1768149a72
@ -1119,6 +1119,10 @@ function esc_telem:get_rpm(instance) end
|
||||
---@param param3 number -- error rate
|
||||
function esc_telem:update_rpm(esc_index, rpm, error_rate) end
|
||||
|
||||
-- set scale factor for RPM on a motor
|
||||
---@param param1 motor index (0 is first motor)
|
||||
---@param param2 scale factor
|
||||
function esc_telem:set_rpm_scale(esc_index, scale_factor) end
|
||||
|
||||
-- desc
|
||||
---@class optical_flow
|
||||
|
@ -311,6 +311,7 @@ singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS f
|
||||
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
|
||||
singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check
|
||||
|
||||
include AP_Param/AP_Param.h
|
||||
singleton AP_Param rename param
|
||||
|
Loading…
Reference in New Issue
Block a user