mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: add set_posvelaccel_offset binding
Co-authored-by: Leonard Hall <leonardthall@gmail.com>
This commit is contained in:
parent
1c59ec8b94
commit
0c81f111fb
|
@ -3723,6 +3723,22 @@ AR_AttitudeControl = {}
|
||||||
---@return number -- spees slew rate
|
---@return number -- spees slew rate
|
||||||
function AR_AttitudeControl:get_srate() end
|
function AR_AttitudeControl:get_srate() end
|
||||||
|
|
||||||
|
-- copter position controller
|
||||||
|
poscontrol = {}
|
||||||
|
|
||||||
|
-- add an offset to position controller's target position, velocity and acceleration
|
||||||
|
---@param pos_offset_NED Vector3f_ud
|
||||||
|
---@param vel_offset_NED Vector3f_ud
|
||||||
|
---@param accel_offset_NED Vector3f_ud
|
||||||
|
---@return boolean
|
||||||
|
function poscontrol:set_posvelaccel_offset(pos_offset_NED, vel_offset_NED, accel_offset_NED) end
|
||||||
|
|
||||||
|
-- get position controller's target position, velocity and acceleration offsets
|
||||||
|
---@return Vector3f_ud|nil
|
||||||
|
---@return Vector3f_ud|nil
|
||||||
|
---@return Vector3f_ud|nil
|
||||||
|
function poscontrol:get_posvelaccel_offset() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
AR_PosControl = {}
|
AR_PosControl = {}
|
||||||
|
|
||||||
|
|
|
@ -759,6 +759,12 @@ include AC_AttitudeControl/AC_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD
|
||||||
singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
singleton AC_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_ArduPlane)||APM_BUILD_COPTER_OR_HELI
|
||||||
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
|
singleton AC_AttitudeControl method get_rpy_srate void float'Ref float'Ref float'Ref
|
||||||
|
|
||||||
|
include AC_AttitudeControl/AC_PosControl.h depends APM_BUILD_COPTER_OR_HELI
|
||||||
|
singleton AC_PosControl depends APM_BUILD_COPTER_OR_HELI
|
||||||
|
singleton AC_PosControl rename poscontrol
|
||||||
|
singleton AC_PosControl method set_posvelaccel_offset boolean Vector3f Vector3f Vector3f
|
||||||
|
singleton AC_PosControl method get_posvelaccel_offset boolean Vector3f'Null Vector3f'Null Vector3f'Null
|
||||||
|
|
||||||
include APM_Control/AR_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
include APM_Control/AR_AttitudeControl.h depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
singleton AR_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
singleton AR_AttitudeControl depends APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||||
singleton AR_AttitudeControl method get_srate void float'Ref float'Ref
|
singleton AR_AttitudeControl method get_srate void float'Ref float'Ref
|
||||||
|
|
Loading…
Reference in New Issue