mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: add AR_AttitudeControl srate binding
also add AP_Vehicle:get_steering_and_throttle binding
This commit is contained in:
parent
eaa2ce17de
commit
35513ba539
@ -1788,6 +1788,11 @@ function vehicle:get_wp_distance_m() end
|
|||||||
---@return boolean
|
---@return boolean
|
||||||
function vehicle:set_steering_and_throttle(steering, throttle) end
|
function vehicle:set_steering_and_throttle(steering, throttle) end
|
||||||
|
|
||||||
|
-- desc
|
||||||
|
---@return number|nil
|
||||||
|
---@return number|nil
|
||||||
|
function vehicle:get_steering_and_throttle() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@param rate_dps number
|
---@param rate_dps number
|
||||||
---@return boolean
|
---@return boolean
|
||||||
@ -2617,6 +2622,15 @@ AC_AttitudeControl = {}
|
|||||||
---@return number -- yaw slew rate
|
---@return number -- yaw slew rate
|
||||||
function AC_AttitudeControl:get_rpy_srate() end
|
function AC_AttitudeControl:get_rpy_srate() end
|
||||||
|
|
||||||
|
-- desc
|
||||||
|
---@class AR_AttitudeControl
|
||||||
|
AR_AttitudeControl = {}
|
||||||
|
|
||||||
|
-- return attitude controller slew rates for rovers
|
||||||
|
---@return number -- steering slew rate
|
||||||
|
---@return number -- spees slew rate
|
||||||
|
function AR_AttitudeControl:get_srate() end
|
||||||
|
|
||||||
-- desc
|
-- desc
|
||||||
---@class follow
|
---@class follow
|
||||||
follow = {}
|
follow = {}
|
||||||
|
@ -262,6 +262,7 @@ singleton AP_Vehicle method set_target_angle_and_climbrate boolean float -180 18
|
|||||||
singleton AP_Vehicle method get_circle_radius boolean float'Null
|
singleton AP_Vehicle method get_circle_radius boolean float'Null
|
||||||
singleton AP_Vehicle method set_circle_rate boolean float'skip_check
|
singleton AP_Vehicle method set_circle_rate boolean float'skip_check
|
||||||
singleton AP_Vehicle method set_steering_and_throttle boolean float -1 1 float -1 1
|
singleton AP_Vehicle method set_steering_and_throttle boolean float -1 1 float -1 1
|
||||||
|
singleton AP_Vehicle method get_steering_and_throttle boolean float'Null float'Null
|
||||||
singleton AP_Vehicle method get_wp_distance_m boolean float'Null
|
singleton AP_Vehicle method get_wp_distance_m boolean float'Null
|
||||||
singleton AP_Vehicle method get_wp_bearing_deg boolean float'Null
|
singleton AP_Vehicle method get_wp_bearing_deg boolean float'Null
|
||||||
singleton AP_Vehicle method get_wp_crosstrack_error_m boolean float'Null
|
singleton AP_Vehicle method get_wp_crosstrack_error_m boolean float'Null
|
||||||
@ -590,6 +591,10 @@ 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 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 method get_srate void float'Ref float'Ref
|
||||||
|
|
||||||
include AP_Mount/AP_Mount.h
|
include AP_Mount/AP_Mount.h
|
||||||
singleton AP_Mount depends HAL_MOUNT_ENABLED == 1
|
singleton AP_Mount depends HAL_MOUNT_ENABLED == 1
|
||||||
singleton AP_Mount rename mount
|
singleton AP_Mount rename mount
|
||||||
|
Loading…
Reference in New Issue
Block a user