From eddbf7a7554a7966137bcf9ccaa66a1422c6b031 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 20 Aug 2020 10:26:52 +0900 Subject: [PATCH] AP_Scripting: fix get_control_output binding co-author: @wicked.shell.scripts@gmail.com --- libraries/AP_Scripting/generator/description/bindings.desc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index bf65eed4dea27..6f36fd42c47ac 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -179,7 +179,7 @@ singleton AP_Vehicle method get_likely_flying boolean singleton AP_Vehicle method get_time_flying_ms uint32_t singleton AP_Vehicle method start_takeoff boolean float (-LOCATION_ALT_MAX_M*100+1) (LOCATION_ALT_MAX_M*100-1) singleton AP_Vehicle method set_target_location boolean Location -singleton AP_Vehicle method get_control_output boolean AP_Vehicle::ControlOutput'enum AP_Vehicle::ControlOutput::Roll AP_Vehicle::ControlOutput::Last_ControlOutput float'Null +singleton AP_Vehicle method get_control_output boolean AP_Vehicle::ControlOutput'enum AP_Vehicle::ControlOutput::Roll ((uint32_t)AP_Vehicle::ControlOutput::Last_ControlOutput-1) float'Null singleton AP_Vehicle method get_target_location boolean Location'Null singleton AP_Vehicle method set_target_velocity_NED boolean Vector3f singleton AP_Vehicle method set_target_angle_and_climbrate boolean float -180 180 float -90 90 float -360 360 float -FLT_MAX FLT_MAX boolean float -FLT_MAX FLT_MAX