mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Scripting: add binding for vehicle set_target_rate_and_throttle
This commit is contained in:
parent
fc327fa370
commit
4894675977
@ -2384,6 +2384,14 @@ function vehicle:get_circle_radius() end
|
||||
---@return boolean
|
||||
function vehicle:set_target_angle_and_climbrate(roll_deg, pitch_deg, yaw_deg, climb_rate_ms, use_yaw_rate, yaw_rate_degs) end
|
||||
|
||||
-- Set vehicles roll, pitch, and yaw rates with throttle in guided mode
|
||||
---@param roll_rate_dps number -- roll rate in degrees per second
|
||||
---@param pitch_rate_dps number -- pitch rate in degrees per second
|
||||
---@param yaw_rate_dps number -- yaw rate in degrees per second
|
||||
---@param throttle number -- throttle demand 0.0 to 1.0
|
||||
---@return boolean -- true if successful
|
||||
function vehicle:set_target_rate_and_throttle(roll_rate_dps, pitch_rate_dps, yaw_rate_dps, throttle) end
|
||||
|
||||
-- Sets the target velocity using a Vector3f object in a guided mode.
|
||||
---@param vel_ned Vector3f_ud -- North, East, Down meters / second
|
||||
---@return boolean -- true on success
|
||||
|
@ -329,6 +329,7 @@ singleton AP_Vehicle method set_target_posvelaccel_NED boolean Vector3f Vector3f
|
||||
singleton AP_Vehicle method set_target_velaccel_NED boolean Vector3f Vector3f boolean float -360 +360 boolean float'skip_check boolean
|
||||
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'skip_check boolean float'skip_check
|
||||
singleton AP_Vehicle method set_target_rate_and_throttle boolean float'skip_check float'skip_check float'skip_check float'skip_check
|
||||
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
|
||||
@ -352,6 +353,7 @@ singleton AP_Vehicle method is_landing boolean
|
||||
singleton AP_Vehicle method is_taking_off boolean
|
||||
singleton AP_Vehicle method set_crosstrack_start boolean Location
|
||||
|
||||
|
||||
include AP_SerialLED/AP_SerialLED.h
|
||||
singleton AP_SerialLED rename serialLED
|
||||
singleton AP_SerialLED depends AP_SERIALLED_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user