mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
AP_Scripting: add binding for set_desired_steering_and_throttle
This commit is contained in:
parent
35f0402b47
commit
d665a0a440
@ -165,6 +165,7 @@ singleton AP_Vehicle method set_target_location boolean Location
|
||||
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
|
||||
singleton AP_Vehicle method set_steering_and_throttle boolean float -1 1 float -1 1
|
||||
|
||||
include AP_SerialLED/AP_SerialLED.h
|
||||
singleton AP_SerialLED alias serialLED
|
||||
|
Loading…
Reference in New Issue
Block a user