From 5e3c0d4ead96968f5afd19915c38278656d666ab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 26 May 2023 13:41:01 +0900 Subject: [PATCH] AP_Scripting: add AR_AttitudeControl srate binding also add AP_Vehicle:get_steering_and_throttle binding --- libraries/AP_Scripting/docs/docs.lua | 14 ++++++++++++++ .../generator/description/bindings.desc | 5 +++++ 2 files changed, 19 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 6b95120dd9..726fb73f53 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1994,6 +1994,11 @@ function vehicle:get_wp_distance_m() end ---@return boolean function vehicle:set_steering_and_throttle(steering, throttle) end +-- desc +---@return number|nil +---@return number|nil +function vehicle:get_steering_and_throttle() end + -- desc ---@param rate_dps number ---@return boolean @@ -2834,6 +2839,15 @@ AC_AttitudeControl = {} ---@return number -- yaw slew rate 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 ---@class follow follow = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index bf0a2c2682..dd212390e5 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -263,6 +263,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 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 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_bearing_deg boolean float'Null singleton AP_Vehicle method get_wp_crosstrack_error_m boolean float'Null @@ -598,6 +599,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 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 singleton AP_Mount depends HAL_MOUNT_ENABLED == 1 singleton AP_Mount rename mount