AP_Scripting: Add getting of gyro/accel values
Added the ability to get gyro/accel from LUA
This commit is contained in:
parent
022e8be735
commit
c259d11cd6
@ -1495,8 +1495,8 @@ ins = {}
|
||||
---@return number
|
||||
function ins:get_temperature(instance) end
|
||||
|
||||
-- Check if a specific gyrometer sensor is healthy
|
||||
---@param instance integer -- the 0-based index of the gyrometer instance to return.
|
||||
-- Check if a specific gyroscope sensor is healthy
|
||||
---@param instance integer -- the 0-based index of the gyroscope instance to return.
|
||||
---@return boolean
|
||||
function ins:get_gyro_health(instance) end
|
||||
|
||||
@ -1509,6 +1509,16 @@ function ins:get_accel_health(instance) end
|
||||
---@return boolean
|
||||
function ins:calibrating() end
|
||||
|
||||
-- Get the value of a specific gyroscope
|
||||
---@param instance integer -- the 0-based index of the gyroscope instance to return.
|
||||
---@return Vector3f_ud
|
||||
function ins:get_gyro(instance) end
|
||||
|
||||
-- Get the value of a specific accelerometer
|
||||
---@param instance integer -- the 0-based index of the accelerometer instance to return.
|
||||
---@return Vector3f_ud
|
||||
function ins:get_accel(instance) end
|
||||
|
||||
-- desc
|
||||
---@class Motors_dynamic
|
||||
Motors_dynamic = {}
|
||||
|
@ -638,6 +638,8 @@ singleton AP_InertialSensor method get_temperature float uint8_t 0 INS_MAX_INSTA
|
||||
singleton AP_InertialSensor method get_gyro_health boolean uint8_t'skip_check
|
||||
singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check
|
||||
singleton AP_InertialSensor method calibrating boolean
|
||||
singleton AP_InertialSensor method get_gyro Vector3f uint8_t'skip_check
|
||||
singleton AP_InertialSensor method get_accel Vector3f uint8_t'skip_check
|
||||
|
||||
singleton CAN manual get_device lua_get_CAN_device 1
|
||||
singleton CAN manual get_device2 lua_get_CAN_device2 1
|
||||
|
Loading…
Reference in New Issue
Block a user