mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Scripting: djirs2 driver supports upsidedown setup
This commit is contained in:
parent
4918bb4705
commit
c80c4adf3e
@ -84,8 +84,9 @@ local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTI
|
||||
|
||||
-- parameters
|
||||
local PARAM_TABLE_KEY = 38
|
||||
assert(param:add_table(PARAM_TABLE_KEY, "DJIR_", 1), "could not add param table")
|
||||
assert(param:add_table(PARAM_TABLE_KEY, "DJIR_", 2), "could not add param table")
|
||||
assert(param:add_param(PARAM_TABLE_KEY, 1, "DEBUG", 0), "could not add DJIR_DEBUG param")
|
||||
assert(param:add_param(PARAM_TABLE_KEY, 2, "UPSIDEDOWN", 0), "could not add DJIR_UPSIDEDOWN param")
|
||||
|
||||
-- bind parameters to variables
|
||||
local CAN_P1_DRIVER = Parameter("CAN_P1_DRIVER") -- If using CAN1, should be 1:First driver
|
||||
@ -96,6 +97,7 @@ local CAN_P2_BITRATE = Parameter("CAN_P2_BITRATE") -- If using CAN2, should
|
||||
local CAN_D2_PROTOCOL = Parameter("CAN_D2_PROTOCOL") -- If using CAN2, should be 10:Scripting
|
||||
local MNT1_TYPE = Parameter("MNT1_TYPE") -- should be 9:Scripting
|
||||
local DJIR_DEBUG = Parameter("DJIR_DEBUG") -- debug level. 0:disabled 1:enabled 2:enabled with attitude reporting
|
||||
local DJIR_UPSIDEDOWN = Parameter("DJIR_UPSIDEDOWN") -- 0:rightsideup, 1:upsidedown
|
||||
|
||||
-- message definitions
|
||||
local HEADER = 0xAA
|
||||
@ -438,6 +440,11 @@ function send_target_angles(roll_angle_deg, pitch_angle_deg, yaw_angle_deg, time
|
||||
yaw_angle_deg = yaw_angle_deg or 0
|
||||
time_sec = time_sec or 2
|
||||
|
||||
-- if upsidedown, add 180deg to yaw
|
||||
if DJIR_UPSIDEDOWN:get() > 0 then
|
||||
yaw_angle_deg = wrap_180(yaw_angle_deg + 180)
|
||||
end
|
||||
|
||||
-- ensure angles are integers
|
||||
roll_angle_deg = -math.floor(roll_angle_deg + 0.5)
|
||||
pitch_angle_deg = math.floor(pitch_angle_deg + 0.5)
|
||||
|
Loading…
Reference in New Issue
Block a user