mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AP_Scripting: add binding for setting motors custom frame string
This commit is contained in:
parent
70897b5e38
commit
cc5a867397
@ -645,6 +645,15 @@ function RC_Channel_ud:get_aux_switch_pos() end
|
||||
function RC_Channel_ud:norm_input() end
|
||||
|
||||
|
||||
-- desc
|
||||
---@class motors
|
||||
motors = {}
|
||||
|
||||
-- desc
|
||||
---@param param1 string
|
||||
function motors:set_frame_string(param1) end
|
||||
|
||||
|
||||
-- desc
|
||||
---@class periph
|
||||
periph = {}
|
||||
|
@ -33,3 +33,5 @@ add_motor(AP_MOTORS_MOT_5, 30, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1)
|
||||
add_motor(AP_MOTORS_MOT_6,-150, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4)
|
||||
|
||||
assert(MotorsMatrix:init(6), "Failed to init MotorsMatrix")
|
||||
|
||||
motors:set_frame_string("fault tolerant hex")
|
||||
|
@ -7,3 +7,5 @@ MotorsMatrix:add_motor_raw(2, 0, 1,-1, 1)
|
||||
MotorsMatrix:add_motor_raw(3, 0,-1,-1, 3)
|
||||
|
||||
assert(MotorsMatrix:init(4), "Failed to init MotorsMatrix")
|
||||
|
||||
motors:set_frame_string("scripting plus example")
|
||||
|
@ -43,5 +43,7 @@ assert(Motors_dynamic:init(4), "Failed to init Motors_dynamic")
|
||||
-- at any time we can then re-load new factors
|
||||
Motors_dynamic:load_factors(factors)
|
||||
|
||||
motors:set_frame_string("Dynamic example")
|
||||
|
||||
-- if doing changes in flight it is a good idea to us pcall to protect the script from crashing
|
||||
-- see 'protected_call.lua' example
|
||||
|
@ -9,3 +9,6 @@ Motors_6DoF:add_motor(4, -0.205533, -0.035715, 0.359267, -0.048371, 0.010753,
|
||||
Motors_6DoF:add_motor(5, 0.143881, -0.227449, 0.375220, -0.046098, 0.811593, 0.431718, true, 6)
|
||||
|
||||
assert(Motors_6DoF:init(6),'unable to setup 6 motors')
|
||||
|
||||
motors:set_frame_string("6DoF example")
|
||||
|
||||
|
@ -452,3 +452,9 @@ singleton AP_Periph_FW depends defined(HAL_BUILD_AP_PERIPH)
|
||||
singleton AP_Periph_FW alias periph
|
||||
singleton AP_Periph_FW method get_yaw_earth float
|
||||
singleton AP_Periph_FW method get_vehicle_state uint32_t
|
||||
|
||||
include AP_Motors/AP_Motors_Class.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AP::motors() depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||
singleton AP::motors() literal
|
||||
singleton AP::motors() alias motors
|
||||
singleton AP::motors() method set_frame_string void string
|
||||
|
Loading…
Reference in New Issue
Block a user