mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add bindings and example for dynamic motor mixer
This commit is contained in:
parent
6848cbc241
commit
d158199a7a
|
@ -0,0 +1,47 @@
|
|||
-- This script is an example setting up a custom dynamic motor matrix
|
||||
-- allowing a vehicle to change geometry in flight
|
||||
|
||||
-- this mixer is for a plus quad copter, the default SITL vehicle.
|
||||
-- Setup motor number (zero indexed) and testing order (1 indexed)
|
||||
Motors_dynamic:add_motor(0, 2)
|
||||
Motors_dynamic:add_motor(1, 4)
|
||||
Motors_dynamic:add_motor(2, 1)
|
||||
Motors_dynamic:add_motor(3, 3)
|
||||
|
||||
factors = motor_factor_table()
|
||||
|
||||
-- Roll for motors 1 - 4
|
||||
factors:roll(0, -0.5)
|
||||
factors:roll(1, 0.5)
|
||||
factors:roll(2, 0)
|
||||
factors:roll(3, 0)
|
||||
|
||||
-- pitch for motors 1 -4
|
||||
factors:pitch(0, 0)
|
||||
factors:pitch(1, 0)
|
||||
factors:pitch(2, 0.5)
|
||||
factors:pitch(3, -0.5)
|
||||
|
||||
-- yaw for motors 1 -4
|
||||
factors:yaw(0, 0.5)
|
||||
factors:yaw(1, 0.5)
|
||||
factors:yaw(2, -0.5)
|
||||
factors:yaw(3, -0.5)
|
||||
|
||||
-- throttle for motors 1 -4
|
||||
factors:throttle(0, 1)
|
||||
factors:throttle(1, 1)
|
||||
factors:throttle(2, 1)
|
||||
factors:throttle(3, 1)
|
||||
|
||||
-- must load factors before init
|
||||
Motors_dynamic:load_factors(factors)
|
||||
|
||||
-- were expecting 4 motors
|
||||
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)
|
||||
|
||||
-- if doing changes in flight it is a good idea to us pcall to protect the script from crashing
|
||||
-- see 'protected_call.lua' example
|
|
@ -334,8 +334,8 @@ singleton QuadPlane method in_vtol_mode boolean
|
|||
include AP_Motors/AP_MotorsMatrix.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
singleton AP_MotorsMatrix depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
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 init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
||||
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
|
||||
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
|
||||
|
@ -354,8 +354,8 @@ singleton AC_AttitudeControl_Multi_6DoF method set_offset_roll_pitch void float
|
|||
include AP_Motors/AP_MotorsMatrix_6DoF_Scripting.h depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting depends APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting alias Motors_6DoF
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting method init boolean uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1)
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting method add_motor 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 float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX boolean uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1)
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
||||
singleton AP_MotorsMatrix_6DoF_Scripting method add_motor 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 float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
||||
|
||||
include AP_HAL/I2CDevice.h
|
||||
ap_object AP_HAL::I2CDevice semaphore-pointer
|
||||
|
@ -385,3 +385,17 @@ singleton hal.gpio method pinMode void uint8_t 0 UINT8_MAX uint8_t 0 1
|
|||
singleton hal.analogin alias analog
|
||||
singleton hal.analogin literal
|
||||
singleton hal.analogin method channel AP_HAL::AnalogSource ANALOG_INPUT_NONE'literal
|
||||
|
||||
include AP_Motors/AP_MotorsMatrix_Scripting_Dynamic.h depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
singleton AP_MotorsMatrix_Scripting_Dynamic depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
singleton AP_MotorsMatrix_Scripting_Dynamic alias Motors_dynamic
|
||||
singleton AP_MotorsMatrix_Scripting_Dynamic method init boolean uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
||||
singleton AP_MotorsMatrix_Scripting_Dynamic method add_motor void uint8_t 0 (AP_MOTORS_MAX_NUM_MOTORS-1) uint8_t 0 AP_MOTORS_MAX_NUM_MOTORS
|
||||
singleton AP_MotorsMatrix_Scripting_Dynamic method load_factors void AP_MotorsMatrix_Scripting_Dynamic::factor_table
|
||||
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table alias motor_factor_table
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field roll'array AP_MOTORS_MAX_NUM_MOTORS float read write -FLT_MAX FLT_MAX
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field pitch'array AP_MOTORS_MAX_NUM_MOTORS float read write -FLT_MAX FLT_MAX
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field yaw'array AP_MOTORS_MAX_NUM_MOTORS float read write -FLT_MAX FLT_MAX
|
||||
userdata AP_MotorsMatrix_Scripting_Dynamic::factor_table field throttle'array AP_MOTORS_MAX_NUM_MOTORS float read write -FLT_MAX FLT_MAX
|
||||
|
|
Loading…
Reference in New Issue