mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Scripting: added bindings for motors roll, pitch, yaw outputs
This commit is contained in:
parent
7fe547cfce
commit
bc3fc9a317
@ -1064,6 +1064,30 @@ function motors:set_frame_string(param1) end
|
||||
---@return integer
|
||||
function motors:get_desired_spool_state() end
|
||||
|
||||
-- get yaw FF output
|
||||
---@return number
|
||||
function motors:get_yaw_ff() end
|
||||
|
||||
-- get yaw P+I+D
|
||||
---@return number
|
||||
function motors:get_yaw() end
|
||||
|
||||
-- get pitch FF out
|
||||
---@return number
|
||||
function motors:get_pitch_ff() end
|
||||
|
||||
-- get pitch P+I+D out
|
||||
---@return number
|
||||
function motors:get_pitch() end
|
||||
|
||||
-- get roll FF out
|
||||
---@return number
|
||||
function motors:get_roll_ff() end
|
||||
|
||||
-- get roll P+I+D
|
||||
---@return number
|
||||
function motors:get_roll() end
|
||||
|
||||
-- desc
|
||||
---@class FWVersion
|
||||
FWVersion = {}
|
||||
|
@ -549,6 +549,12 @@ singleton AP::motors() rename motors
|
||||
singleton AP::motors() method set_frame_string void string
|
||||
singleton AP::motors() method get_interlock boolean
|
||||
singleton AP::motors() method get_desired_spool_state uint8_t
|
||||
singleton AP::motors() method get_roll float
|
||||
singleton AP::motors() method get_roll_ff float
|
||||
singleton AP::motors() method get_pitch float
|
||||
singleton AP::motors() method get_pitch_ff float
|
||||
singleton AP::motors() method get_yaw float
|
||||
singleton AP::motors() method get_yaw_ff float
|
||||
|
||||
include AP_Common/AP_FWVersion.h
|
||||
singleton AP::fwversion() literal
|
||||
|
Loading…
Reference in New Issue
Block a user