mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_Scripting: add set_target_posvel_NED binding
This commit is contained in:
parent
d5715292a3
commit
1a3a2a0437
@ -186,6 +186,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 set_target_posvel_NED boolean Vector3f Vector3f
|
||||
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
|
||||
|
Loading…
Reference in New Issue
Block a user