Browse Source

AP_Scripting: fix get_control_output binding

co-author: @wicked.shell.scripts@gmail.com
zr-v5.1
Randy Mackay 5 years ago
parent
commit
eddbf7a755
  1. 2
      libraries/AP_Scripting/generator/description/bindings.desc

2
libraries/AP_Scripting/generator/description/bindings.desc

@ -179,7 +179,7 @@ singleton AP_Vehicle method get_likely_flying boolean @@ -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

Loading…
Cancel
Save