Skip to content

Commit

Permalink
AP_Scripting: add set_target_angle_and_thrust() and get_throttle_in()
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Dec 17, 2023
1 parent 15166e9 commit 5cee51e
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 0 deletions.
14 changes: 14 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -1297,6 +1297,10 @@ function motors:get_forward() end
---@return number
function motors:get_throttle() end

-- get thrust motor input
---@return number
function motors:get_throttle_in() end

-- get throttle motor output
---@return integer
---| '0' # Shut down
Expand Down Expand Up @@ -2095,6 +2099,16 @@ 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

-- desc
---@param roll_deg number
---@param pitch_deg number
---@param yaw_deg number
---@param thrust number
---@param use_yaw_rate boolean
---@param yaw_rate_degs number
---@return boolean
function vehicle:set_target_angle_and_thrust(roll_deg, pitch_deg, yaw_deg, thrust, use_yaw_rate, yaw_rate_degs) end

-- desc
---@param vel_ned Vector3f_ud
---@param align_yaw_to_target? boolean
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -285,6 +285,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 boolean
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_angle_and_thrust boolean float -180 180 float -90 90 float -360 360 float'skip_check boolean 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
Expand Down Expand Up @@ -625,6 +626,7 @@ singleton AP::motors() method get_pitch_ff float
singleton AP::motors() method get_yaw float
singleton AP::motors() method get_yaw_ff float
singleton AP::motors() method get_throttle float
singleton AP::motors() method get_throttle_in float
singleton AP::motors() method get_forward float
singleton AP::motors() method get_lateral float
singleton AP::motors() method get_spool_state uint8_t
Expand Down

0 comments on commit 5cee51e

Please sign in to comment.