From eb752a8397e9c325b44d3a59038a5305202ebff4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 10 Feb 2023 15:49:52 +0900 Subject: [PATCH] AP_Scripting: djirs2 comment fix --- libraries/AP_Scripting/drivers/mount-djirs2-driver.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index c8603ba2c3..75d17b88a1 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -511,7 +511,7 @@ function send_target_rates(roll_rate_degs, pitch_rate_degs, yaw_rate_degs) -- Field name SOF LenL LenH CmdTyp Enc RES RES RES SeqL SeqH CrcL CrcH CmdSet CmdId YawL YawH RollL RollH PitL PitH Ctrl CRC32 CRC32 CRC32 CRC32 local set_target_speed_msg = {0xAA, 0x19, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0E, 0x01, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x88, 0x00, 0x00, 0x00, 0x00} - -- set angles + -- set rates set_target_speed_msg[15] = lowbyte(yaw_rate_degs * 10) set_target_speed_msg[16] = highbyte(yaw_rate_degs * 10) set_target_speed_msg[17] = lowbyte(roll_rate_degs * 10)