mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AP_Scripting: add motor matrix set throttle factor binding
This commit is contained in:
parent
42538c7083
commit
c239e71de5
@ -323,6 +323,7 @@ singleton AP_MotorsMatrix depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD
|
||||
singleton AP_MotorsMatrix alias MotorsMatrix
|
||||
singleton AP_MotorsMatrix method init boolean uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1)
|
||||
singleton AP_MotorsMatrix method add_motor_raw void int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1)
|
||||
singleton AP_MotorsMatrix method set_throttle_factor boolean int8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) float 0 FLT_MAX
|
||||
|
||||
include AP_Frsky_Telem/AP_Frsky_SPort.h
|
||||
singleton AP_Frsky_SPort alias frsky_sport
|
||||
|
Loading…
Reference in New Issue
Block a user