mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-19 07:08:29 -04:00
AP_Scripting: add bindings for servo telem
This commit is contained in:
parent
2d57944280
commit
decfeeeaf5
@ -4015,7 +4015,6 @@ function networking:get_netmask_active() end
|
||||
function networking:get_ip_active() end
|
||||
|
||||
-- visual odometry object
|
||||
--@class visual_odom
|
||||
visual_odom = {}
|
||||
|
||||
-- visual odometry health
|
||||
@ -4025,3 +4024,59 @@ function visual_odom:healthy() end
|
||||
-- visual odometry quality as a percentage from 1 to 100 or 0 if unknown
|
||||
---@return integer
|
||||
function visual_odom:quality() end
|
||||
|
||||
-- servo telemetry class
|
||||
servo_telem = {}
|
||||
|
||||
-- get servo telem for the given servo number
|
||||
---@param servo_index integer -- 0 indexed servo number
|
||||
---@return AP_Servo_Telem_Data_ud|nil
|
||||
function servo_telem:get_telem(servo_index) end
|
||||
|
||||
-- Servo telemtry userdata object
|
||||
---@class AP_Servo_Telem_Data_ud
|
||||
local AP_Servo_Telem_Data_ud = {}
|
||||
|
||||
-- Get timestamp of last telem update
|
||||
---@return uint32_t_ud -- milliseconds since boot
|
||||
function AP_Servo_Telem_Data_ud:last_update_ms() end
|
||||
|
||||
-- Get type spesfic status flags
|
||||
---@return integer|nil -- flags or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:status_flags() end
|
||||
|
||||
-- Get pcb temprature in centidegrees
|
||||
---@return integer|nil -- temperature in centidegrees or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:pcb_temperature_cdeg() end
|
||||
|
||||
-- Get motor temprature in centidegrees
|
||||
---@return integer|nil -- temperature in centidegrees or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:motor_temperature_cdeg() end
|
||||
|
||||
-- Get duty cycle
|
||||
---@return integer|nil -- duty cycle 0% to 100% or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:duty_cycle() end
|
||||
|
||||
-- get current
|
||||
---@return number|nil -- current in amps or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:current() end
|
||||
|
||||
-- get voltage
|
||||
---@return number|nil -- voltage in volts or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:voltage() end
|
||||
|
||||
-- get speed
|
||||
---@return number|nil -- speed in degrees per second or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:speed() end
|
||||
|
||||
-- get force
|
||||
---@return number|nil -- force in newton meters or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:force() end
|
||||
|
||||
-- get measured position
|
||||
---@return number|nil -- measured position in degrees or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:measured_position() end
|
||||
|
||||
-- get commanded position
|
||||
---@return number|nil -- comanded position in degrees or nil if not available
|
||||
function AP_Servo_Telem_Data_ud:command_position() end
|
||||
|
@ -1042,3 +1042,23 @@ include AP_TemperatureSensor/AP_TemperatureSensor.h
|
||||
singleton AP_TemperatureSensor depends AP_TEMPERATURE_SENSOR_ENABLED
|
||||
singleton AP_TemperatureSensor rename temperature_sensor
|
||||
singleton AP_TemperatureSensor method get_temperature boolean float'Null uint8_t'skip_check
|
||||
|
||||
include AP_Servo_Telem/AP_Servo_Telem.h depends AP_SERVO_TELEM_ENABLED
|
||||
include AP_Servo_Telem/AP_Servo_Telem_config.h
|
||||
singleton AP_Servo_Telem depends AP_SERVO_TELEM_ENABLED
|
||||
singleton AP_Servo_Telem rename servo_telem
|
||||
singleton AP_Servo_Telem method get_telem boolean uint8_t'skip_check AP_Servo_Telem::TelemetryData'Null
|
||||
|
||||
userdata AP_Servo_Telem::TelemetryData depends AP_SERVO_TELEM_ENABLED
|
||||
userdata AP_Servo_Telem::TelemetryData rename AP_Servo_Telem_Data
|
||||
userdata AP_Servo_Telem::TelemetryData field command_position float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::COMMANDED_POSITION
|
||||
userdata AP_Servo_Telem::TelemetryData field measured_position float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::MEASURED_POSITION
|
||||
userdata AP_Servo_Telem::TelemetryData field force float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::FORCE
|
||||
userdata AP_Servo_Telem::TelemetryData field speed float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::SPEED
|
||||
userdata AP_Servo_Telem::TelemetryData field voltage float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::VOLTAGE
|
||||
userdata AP_Servo_Telem::TelemetryData field current float'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::CURRENT
|
||||
userdata AP_Servo_Telem::TelemetryData field duty_cycle uint8_t'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::DUTY_CYCLE
|
||||
userdata AP_Servo_Telem::TelemetryData field motor_temperature_cdeg int16_t'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::MOTOR_TEMP
|
||||
userdata AP_Servo_Telem::TelemetryData field pcb_temperature_cdeg int16_t'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::PCB_TEMP
|
||||
userdata AP_Servo_Telem::TelemetryData field status_flags uint8_t'skip_check read valid_mask valid_types AP_Servo_Telem::TelemetryData::Types::STATUS
|
||||
userdata AP_Servo_Telem::TelemetryData field last_update_ms uint32_t'skip_check read
|
||||
|
Loading…
Reference in New Issue
Block a user