diff --git a/libraries/AP_Scripting/drivers/mount-topotek-driver.lua b/libraries/AP_Scripting/drivers/mount-topotek-driver.lua new file mode 100755 index 00000000000000..f4f10fd5b7ffc0 --- /dev/null +++ b/libraries/AP_Scripting/drivers/mount-topotek-driver.lua @@ -0,0 +1,833 @@ +-- mount-topotek-driver.lua: Topotek mount/gimbal driver + +--[[ + How to use + Connect gimbal UART to one of the autopilot's serial ports + Set SERIALx_PROTOCOL = 28 (Scripting) where "x" corresponds to the serial port connected to the gimbal + Set SERIALx_BAUD = 115 (115200) + Set SCR_ENABLE = 1 to enable scripting and reboot the autopilot + Set MNT1_TYPE = 9 (Scripting) to enable the mount/gimbal scripting driver + Set CAM1_TYPE = 7 (Scripting) to enable the camera scripting driver + Set RCx_OPTION = 300 (Scripting1) to control which camera's picture-in-picture mode. + Set SCR_HEAP_SIZE = 120000 + Copy this script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot + Set MNT1_RC_RATE to 90 (deg/s) to control gimbal movement. + Optionally set TOPK_DEBUG = 1 or 2 to increase level of debug output to the GCS + Reboot the autopilot + + Packet format + Field Index Bytes Description + ------------------------------------------------------------------------------------------- + Frame Header 0 3 type of command + Address Bit 3 2 the source address comes first, and the destination address comes last + Data_Len 5 1 data length + Control Bit 6 1 r -> query w -> setup and control + Identification Bit 7 3 identification function + Data 10 Data_Len + Check Bit 2 the frame header is converted to HEX before reaching the check bit, + the sum is done, and the result is converted to ASC-II. Two bytes, the high one first + +--]] + +-- parameters +local PARAM_TABLE_KEY = 138 +assert(param:add_table(PARAM_TABLE_KEY, "TOPK_", 1), "could not add param table") +assert(param:add_param(PARAM_TABLE_KEY, 1, "DEBUG", 0), "could not add TOPK_DEBUG param") + +-- bind parameters to variables +local MNT1_TYPE = Parameter("MNT1_TYPE") -- should be 9:Scripting +local CAM1_TYPE = Parameter("CAM1_TYPE") -- should be 7:Scripting + +--[[ + // @Param: TOPK_DEBUG + // @DisplayName: Topotek debug + // @Description: Topotek debug + // @Values: 0:Disabled, 1:Enabled, 2:Enabled including attitude reporting + // @User: Advanced +--]] +local TOPK_DEBUG = Parameter("TOPK_DEBUG") -- debug level. 0:disabled 1:enabled 2:enabled with attitude reporting + +-- global definitions +local CAM_PIP_RC_OPTION = 300 -- rc channel option used to control which camera's picture-in-picture mode. RCx_OPTION = 300 (scripting1) +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} +local INIT_INTERVAL_MS = 3000 -- attempt to initialise the gimbal at this interval +local UPDATE_INTERVAL_MS = 100 -- update at 10hz +local MOUNT_INSTANCE = 0 -- always control the first mount/gimbal +local CAMERA_INSTANCE = 0 -- always use the first camera +local ANGULAR_VELOCITY_CONVERSION = 1.220740379 -- gimbal angular velocity conversion ratio +local TRACK_TOTAL_WIDTH = 1920 -- track the maximum width of the image range +local TRACK_TOTAL_HEIGHT = 1080 -- track the maximum height of the image range +local TRACK_RANGE = 60 -- the size of the image at point tracking + +-- local variables and definitions +local uart -- uart object connected to mount +local initialised = false -- true once connection to gimbal has been initialised +local gimbal_stop_order_count = 0 -- record the number of times the stop command is sent to the gimbal. +local cam_pic_count = 0 -- last picture count. used to detect trigger pic +local cam_rec_video = false -- last record video state. used to detect record video +local cam_zoom_type = 0 -- last zoom type 1:Rate 2:Pct +local cam_zoom_value = 0 -- last zoom value. If rate, zoom out = -1, hold = 0, zoom in = 1. If Pct then value from 0 to 100 +local cam_focus_type = 0 -- last focus type 1:Rate, 2:Pct, 4:Auto +local cam_focus_value = 0 -- last focus value. If Rate then focus in = -1, focus hold = 0, focus out = 1 +local last_tracking_type = 0 -- last recorded tracking type (0:None, 1:Point, 2:Rectangle) +local last_tracking_p1x = 0 -- last recorded tracking point1 (used for center or top-left) +local last_tracking_p1y = 0 -- last recorded tracking point1 (used for center or top-left) +local last_tracking_p2x = 0 -- last recorded tracking point2 (bottom-right) +local last_tracking_p2y = 0 -- last recorded tracking point2 (bottom-right) +local cam_pip_status = 0 -- last recorded picture-in-picture mode state will be switched to the next one if it is inconsistent with the current state. +local gimbal_lock = false -- last recorded recorded lock mod. true indicates locked, false indicates followed +local is_tracking = false -- last recorded gimbal tracking mode. true indicates currently tracking, false indicates tracking stopped. +local SD_status = false -- last recorded status of the gimbal's SD card. true indicates normal status, false indicates abnormal status. +local zoom_stop = false -- when the stop command for zoom is sent, this value will be true, allowing the stop command to be resent in the next loop. +local focus_stop = false -- when the stop command for focus is sent, this value will be true, allowing the stop command to be resent in the next loop. +local recv_msg_buff = {} -- data received from the gimbal. +local send_count = 0 -- send data count to the gimbal to control the sending frequency. +local char_map = {} -- store the ASCII values corresponding to 1~9, A~F. +local number_map = {} -- store the hexadecimal values corresponding to 1~9, A~F, a~f. +-- send hard coded message +function send_msg(msg) + + local send_msg = add_check(msg) + for i=1,#send_msg do + uart:write(send_msg[i]) + end +end + +-- calculate the checksum for the data to be sent. +function send_calculate_crc(msg) + local crc = 0; + for i=1, #msg do + crc = crc + msg[i] + end + return crc & 0xFF +end + +-- calculate the checksum for the data to be received. +function recv_calculate_crc(msg) + local crc = 0; + for i=1, #msg - 2 do + crc = crc + msg[i] + end + return crc & 0xFF +end + +-- add check +function add_check(msg) + local crc = send_calculate_crc(msg) + local len = #msg + msg[len + 1] = char_map[(crc>>4) & 0x0F] + msg[len + 2] = char_map[(crc) & 0x0F] + return msg +end + + +-- send stop commands twice to prevent the gimbal from not receiving the command +function repeat_stop_cmd() + if zoom_stop then + local zoom_stop_cmd = {35, 84, 80, 85, 77, 50, 119, 90, 77, 67, 48, 48} + send_msg(zoom_stop_cmd) -- zoom stop + zoom_stop = false + end + + if focus_stop then + local focus_stop_cmd = {35, 84, 80, 85, 77, 50, 119, 70, 67, 67, 48, 48} + send_msg(focus_stop_cmd) -- focus stop + focus_stop = false + end +end + +-- attitude information analysis of gimbal +function gimbal_angle_analyse() + + if #recv_msg_buff < 22 then + return + end + + local yaw = number_map[recv_msg_buff[11]]<<12 | number_map[recv_msg_buff[12]]<<8 | number_map[recv_msg_buff[13]]<<4 | number_map[recv_msg_buff[14]] + local pitch = number_map[recv_msg_buff[15]]<<12 | number_map[recv_msg_buff[16]]<<8 | number_map[recv_msg_buff[17]]<<4 | number_map[recv_msg_buff[18]] + local roll = number_map[recv_msg_buff[19]]<<12 | number_map[recv_msg_buff[20]]<<8 | number_map[recv_msg_buff[21]]<<4 | number_map[recv_msg_buff[22]] + + if yaw > 32767 then + yaw = yaw - 65536 + end + + if pitch > 32767 then + pitch = pitch - 65536 + end + + if roll > 32767 then + roll = roll - 65536 + end + + if 18000 < yaw then + yaw = yaw - 36000 + elseif -18000 > yaw then + yaw = yaw + 36000 + end + + -- divide the data by 100 to obtain the actual value. + roll = roll / 100 + pitch = pitch / 100 + yaw = yaw / 100 + + if TOPK_DEBUG:get() > 1 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: gimbal angle roll:"..roll.." pitch:"..pitch.." yaw:"..yaw) + end +end + +-- gimbal video information analysis +function gimbal_record_analyse() + + if #recv_msg_buff < 12 then + return + end + if recv_msg_buff[11] == 49 or recv_msg_buff[12] == 49 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: start recording") + return + end + + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: stop recording") +end + +-- information analysis of gimbal storage card +function gimbal_sdcard_analyse() + + if #recv_msg_buff < 14 then + return + end + if recv_msg_buff[11] == 78 and recv_msg_buff[12] == 78 and recv_msg_buff[13] == 78 and recv_msg_buff[14] == 78 then + SD_status = false + return + end + + SD_status = true +end + +-- gimbal tracking information analysis +function gimbal_track_analyse() + + if #recv_msg_buff < 12 then + return + end + local track_status = recv_msg_buff[12]; + if track_status == 48 then + gcs:send_text(MAV_SEVERITY.WARNING, "Topotek: trace exception") + elseif track_status == 49 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: stop tracking") + else + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: be tracking") + end +end + +-- analyze the data information received +function analyse_data() + if #recv_msg_buff > 10 then + local crc = recv_calculate_crc(recv_msg_buff) + if char_map[(crc>>4) & 0x0F] == recv_msg_buff[#recv_msg_buff - 1] and char_map[crc & 0x0F] == recv_msg_buff[#recv_msg_buff] then + if recv_msg_buff[8] == 71 and recv_msg_buff[9] == 65 and recv_msg_buff[10] == 67 then + gimbal_angle_analyse() + elseif recv_msg_buff[8] == 72 and recv_msg_buff[9] == 69 and recv_msg_buff[10] == 67 then + gimbal_record_analyse() + elseif recv_msg_buff[8] == 83 and recv_msg_buff[9] == 68 and recv_msg_buff[10] == 67 then + gimbal_sdcard_analyse() + elseif recv_msg_buff[8] == 84 and recv_msg_buff[9] == 82 and recv_msg_buff[10] == 67 then + gimbal_track_analyse() + end + end + end + recv_msg_buff = {} +end + +-- reading incoming packets from gimbal +function read_incoming_packets() + local n_bytes = uart:available() + if n_bytes <= 0 then + return + end + + if n_bytes > 128 then + n_bytes = 128 + while n_bytes > 0 do + n_bytes = n_bytes - 1 + uart:read() + end + do return end + end + + local recv_msg_len = 1 + while n_bytes > 0 do + n_bytes = n_bytes - 1 + local b = uart:read() + if b then + if #recv_msg_buff ~= 0 or b == 35 then + if #recv_msg_buff ~= 0 and b == 35 then + analyse_data() + recv_msg_len = 1; + end + recv_msg_buff[recv_msg_len] = b + recv_msg_len = recv_msg_len + 1 + end + end + end + + analyse_data() +end + +-- send the angles for yaw and pitch. +function set_yaw_pitch_angle(yaw_angle_hund, pitch_angle_hund, speed) + -- set gimbal yaw and pitch angle command + local set_yaw_pitch_angle_cmd = {35, 116, 112, 85, 71, 99, 119, 71, 65, 77} + + set_yaw_pitch_angle_cmd[11] = char_map[(yaw_angle_hund>>12) & 0x0F] + set_yaw_pitch_angle_cmd[12] = char_map[(yaw_angle_hund>>8) & 0x0F] + set_yaw_pitch_angle_cmd[13] = char_map[(yaw_angle_hund>>4) & 0x0F] + set_yaw_pitch_angle_cmd[14] = char_map[(yaw_angle_hund) & 0x0F] + + set_yaw_pitch_angle_cmd[15] = char_map[(speed>>4) & 0x0F] + set_yaw_pitch_angle_cmd[16] = char_map[(speed) & 0x0F] + + set_yaw_pitch_angle_cmd[17] = char_map[(pitch_angle_hund>>12) & 0x0F] + set_yaw_pitch_angle_cmd[18] = char_map[(pitch_angle_hund>>8) & 0x0F] + set_yaw_pitch_angle_cmd[19] = char_map[(pitch_angle_hund>>4) & 0x0F] + set_yaw_pitch_angle_cmd[20] = char_map[(pitch_angle_hund) & 0x0F] + + set_yaw_pitch_angle_cmd[21] = char_map[(speed>>4) & 0x0F] + set_yaw_pitch_angle_cmd[22] = char_map[(speed) & 0x0F] + + send_msg(set_yaw_pitch_angle_cmd) +end + +-- send the angles for roll +function set_roll_angle(roll_angle_hund, speed) + -- set gimbal roll angle command + local set_roll_angle_cmd = {35, 116, 112, 85, 71, 54, 119, 71, 65, 82} + + set_roll_angle_cmd[11] = char_map[(roll_angle_hund>>12) & 0x0F] + set_roll_angle_cmd[12] = char_map[(roll_angle_hund>>8) & 0x0F] + set_roll_angle_cmd[13] = char_map[(roll_angle_hund>>4) & 0x0F] + set_roll_angle_cmd[14] = char_map[(roll_angle_hund) & 0x0F] + + set_roll_angle_cmd[15] = char_map[(speed>>4) & 0x0F] + set_roll_angle_cmd[16] = char_map[(speed) & 0x0F] + + send_msg(set_roll_angle_cmd) +end + +-- send target angles (in degrees) to gimbal +function send_target_angles(roll_angle_deg, pitch_angle_deg, yaw_angle_deg) + + local speed = 99; + + local roll_angle_hund = math.floor(roll_angle_deg*100) + local pitch_angle_hund = math.floor(pitch_angle_deg*100) + local yaw_angle_hund = math.floor(yaw_angle_deg*100) + + -- send the angles for yaw and pitch. + set_yaw_pitch_angle(yaw_angle_hund, pitch_angle_hund, speed) + + -- send the angles for yaw and pitch. + set_roll_angle(roll_angle_hund, speed) +end + +-- send target rates (in deg/sec) to gimbal +function send_target_rates(roll_angle_rate, pitch_angle_rate, yaw_angle_rate) + + -- set the speed of gimbal yaw, pitch and roll command + local set_yaw_pitch_roll_rate_cmd = {35, 116, 112, 85, 71, 54, 119, 89, 80, 82} + -- stop control of the gimbal command + local gimbal_control_stop = {35, 84, 80, 85, 71, 50, 119, 80, 84, 90, 48, 48} + + -- stop sending control commands if the angular velocity is too low. + if roll_angle_rate >= -0.0001 and roll_angle_rate <= 0.0001 and pitch_angle_rate >= -0.0001 and pitch_angle_rate <= 0.0001 and yaw_angle_rate >= -0.0001 and yaw_angle_rate <= 0.0001 then + -- send a stop command. + if gimbal_stop_order_count < 3 then + send_msg(gimbal_control_stop) + gimbal_stop_order_count = gimbal_stop_order_count + 1; + end + return + end + + local roll_angle_rate_conv = 0; + local pitch_angle_rate_conv = 0; + local yaw_angle_rate_conv = 0; + + gimbal_stop_order_count = 0 + + -- ensure that the speed is within a reasonable range. + if roll_angle_rate >= 0 then + roll_angle_rate_conv = math.floor(roll_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if roll_angle_rate_conv > 99 then + roll_angle_rate_conv = 99 + end + else + roll_angle_rate_conv = math.floor(roll_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if roll_angle_rate_conv < -99 then + roll_angle_rate_conv = -99 + end + end + + if pitch_angle_rate >= 0 then + pitch_angle_rate_conv = math.floor(pitch_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if pitch_angle_rate_conv > 99 then + pitch_angle_rate_conv = 99 + end + else + pitch_angle_rate_conv = math.floor(pitch_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if pitch_angle_rate_conv < -99 then + pitch_angle_rate_conv = -99 + end + end + + if yaw_angle_rate >= 0 then + yaw_angle_rate_conv = math.floor(yaw_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if yaw_angle_rate_conv > 99 then + yaw_angle_rate_conv = 99 + end + else + yaw_angle_rate_conv = math.floor(yaw_angle_rate*ANGULAR_VELOCITY_CONVERSION) + if yaw_angle_rate_conv < -99 then + yaw_angle_rate_conv = -99 + end + end + + set_yaw_pitch_roll_rate_cmd[11] = char_map[(yaw_angle_rate_conv>>4)&0x0F] + set_yaw_pitch_roll_rate_cmd[12] = char_map[(yaw_angle_rate_conv)&0x0F] + + set_yaw_pitch_roll_rate_cmd[13] = char_map[(pitch_angle_rate_conv>>4)&0x0F] + set_yaw_pitch_roll_rate_cmd[14] = char_map[(pitch_angle_rate_conv)&0x0F] + + set_yaw_pitch_roll_rate_cmd[15] = char_map[(roll_angle_rate_conv>>4)&0x0F] + set_yaw_pitch_roll_rate_cmd[16] = char_map[(roll_angle_rate_conv)&0x0F] + + send_msg(set_yaw_pitch_roll_rate_cmd) +end + +-- set whether the gimbal is locked or followed command +function set_gimbal_lock(lock) + if gimbal_lock ~= lock then + gimbal_lock = lock + -- gimbal is followed + local gimbal_lock_mode = {35, 84, 80, 85, 71, 50, 119, 80, 84, 90, 48, 55} + if lock then + -- gimbal is locked + gimbal_lock_mode[12] = 54 + end + send_msg(gimbal_lock_mode) + end +end + +-- take picture +function take_pic(cam_state) + if cam_state:take_pic_incr() and cam_state:take_pic_incr() ~= cam_pic_count then + cam_pic_count = cam_state:take_pic_incr() + if SD_status then + -- take a picture command. + local take_pic = {35, 84, 80, 85, 68, 50, 119, 67, 65, 80, 48, 49} + send_msg(take_pic) -- take a photo + if TOPK_DEBUG:get() > 0 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("Topotek: took pic %u", cam_pic_count)) + end + else + gcs:send_text(MAV_SEVERITY.WARNING, "Topotek: no sd card") + end + end +end + +-- recording video +function record_video(cam_state) + if cam_state:recording_video() ~= cam_rec_video then + cam_rec_video = cam_state:recording_video() + + -- record video command. + local record_cmd = {35, 84, 80, 85, 68, 50, 119, 82, 69, 67, 49, 49} + if cam_rec_video > 0 then + if SD_status == false then + gcs:send_text(MAV_SEVERITY.WARNING, "Topotek: no sd card:") + do return end + end + else + -- stop recording + record_cmd[11] = 48 + record_cmd[12] = 48 + end + send_msg(record_cmd) + if TOPK_DEBUG:get() > 0 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: rec video:" .. tostring(cam_rec_video)) + end + end +end + +-- set zoom specified as a rate +function set_cam_zoom(cam_state) + -- zoom out = -1, hold = 0, zoom in = 1 + local zoom_type_changed = cam_state:zoom_type() and (cam_state:zoom_type() ~= cam_zoom_type) + local zoom_value_changed = cam_state:zoom_value() and (cam_state:zoom_value() ~= cam_zoom_value) + if (zoom_type_changed or zoom_value_changed) then + cam_zoom_type = cam_state:zoom_type() + cam_zoom_value = cam_state:zoom_value() + + -- zoom control command + local zoom_cmd = {35, 84, 80, 85, 77, 50, 119, 90, 77, 67, 48, 48} + if cam_zoom_type == 1 then + if cam_zoom_value < 0 then + -- zoom out + zoom_cmd[12] = 49 + elseif cam_zoom_value > 0 then + -- zoom in + zoom_cmd[12] = 50 + else + -- zoom stop + zoom_stop = true + end + end + send_msg(zoom_cmd) + if TOPK_DEBUG:get() > 0 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: zoom type:" .. tostring(cam_zoom_type) .. " value:" .. tostring(cam_zoom_value)) + end + end +end + +-- set camera picture-in-picture mode +function set_cam_pip() + if cam_pip_status ~= rc:get_aux_cached(CAM_PIP_RC_OPTION) then + -- switch to picture-in-picture mode command. + local next_pip_mode = {35, 84, 80, 85, 68, 50, 119, 80, 73, 80, 48, 65}; + send_msg(next_pip_mode) -- picture-in-picture + cam_pip_status = rc:get_aux_cached(CAM_PIP_RC_OPTION) + end +end + +function set_cam_focus(cam_state) + -- focus in = -1, focus hold = 0, focus out = 1 + local focus_type_changed = cam_state:focus_type() and (cam_state:focus_type() ~= cam_focus_type) + local focus_value_changed = cam_state:focus_value() and (cam_state:focus_value() ~= cam_focus_value) + if (focus_type_changed or focus_value_changed) then + cam_focus_type = cam_state:focus_type() + cam_focus_value = cam_state:focus_value() + -- focus-related command. + local focus_cmd = {35, 84, 80, 85, 77, 50, 119, 70, 67, 67, 48, 48} + -- focus rate + if cam_focus_type == 1 then + if cam_focus_value < 0 then + -- focus- + focus_cmd[12] = 50 + elseif cam_focus_value == 0 then + -- focus stop + focus_stop = true + elseif cam_focus_value > 0 then + -- focus+ + focus_cmd[12] = 49 + end + if TOPK_DEBUG:get() > 0 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: focus") + end + end + + -- check auto focus + if cam_focus_type == 4 then + -- auto focus + focus_cmd[11] = 49 + if TOPK_DEBUG:get() > 0 then + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: auto focus") + end + end + send_msg(focus_cmd) + + end +end + +-- check for changes in camera state and send messages to gimbal if required +function check_camera_state() + + -- get latest camera state from AP driver + local cam_state = camera:get_state(CAMERA_INSTANCE) + if not cam_state then + return + end + + -- set camera picture-in-picture mode + set_cam_pip() + + -- check for take picture + take_pic(cam_state) + + -- check for start/stop recording video + record_video(cam_state) + + -- check zoom + set_cam_zoom(cam_state) + + -- check manual focus + set_cam_focus(cam_state) + +end + +-- tracking point +function track_point(tracking_p1x, tracking_p1y) + -- turn tracking point on + local track_point_x = math.floor((tracking_p1x*TRACK_TOTAL_WIDTH - 960) / 0.96) + local track_point_y = math.floor((tracking_p1y*TRACK_TOTAL_HEIGHT - 540) / 0.54) + + -- tracking range after conversion + local track_width = math.floor(TRACK_RANGE/0.96) + local track_height = math.floor(TRACK_RANGE/0.54) + -- begin track command + local begin_track_cmd = {35, 116, 112, 85, 68, 65, 119, 76, 79, 67} + + begin_track_cmd[11] = (track_point_x >> 8) & 0xFF + begin_track_cmd[12] = (track_point_x) & 0xFF + + begin_track_cmd[13] = (track_point_y >> 8) & 0xFF + begin_track_cmd[14] = (track_point_y) & 0xFF + + begin_track_cmd[15] = (track_width >> 8) & 0xFF + begin_track_cmd[16] = (track_width) & 0xFF + + begin_track_cmd[17] = (track_height >> 8) & 0xFF + begin_track_cmd[18] = (track_height) & 0xFF + + begin_track_cmd[19] = 0 + begin_track_cmd[20] = 1 + + send_msg(begin_track_cmd) + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: tracking point ON") +end + +-- tracking rectangle +function tracking_rect(tracking_p1x, tracking_p1y, tracking_p2x, tracking_p2y) + -- upper left point + local upper_leftx; + local upper_lefty; + + -- bottom right point + local down_rightx; + local down_righty; + + -- frame selection range + local frame_selection_width; + local frame_selection_height; + + if tracking_p1x < tracking_p2x then + upper_leftx = tracking_p1x*TRACK_TOTAL_WIDTH + down_rightx = tracking_p2x*TRACK_TOTAL_WIDTH + else + down_rightx = tracking_p1x*TRACK_TOTAL_WIDTH + upper_leftx = tracking_p2x*TRACK_TOTAL_WIDTH + end + + if tracking_p1y < tracking_p2y then + upper_lefty = tracking_p1y*TRACK_TOTAL_HEIGHT + down_righty = tracking_p2y*TRACK_TOTAL_HEIGHT + else + down_righty = tracking_p1y*TRACK_TOTAL_HEIGHT + upper_lefty = tracking_p2y*TRACK_TOTAL_HEIGHT + end + + -- calculated tracking range + frame_selection_width = down_rightx - upper_leftx; + frame_selection_height = down_righty - upper_lefty; + + if frame_selection_width <= 0 or frame_selection_height <= 0 then + return + end + + -- the converted tracking center + local track_center_x = math.floor((upper_leftx + frame_selection_width/2 - 960) / 0.96) + local track_center_y = math.floor((upper_lefty + frame_selection_height/2 - 540) / 0.54) + + -- tracking range after conversion + local track_width = math.floor(frame_selection_width / 0.96) + local track_height = math.floor(frame_selection_height / 0.54) + + + -- begin track command + local begin_track_cmd = {35, 116, 112, 85, 68, 65, 119, 76, 79, 67} + + begin_track_cmd[11] = (track_center_x >> 8) & 0xFF + begin_track_cmd[12] = (track_center_x) & 0xFF + + begin_track_cmd[13] = (track_center_y >> 8) & 0xFF + begin_track_cmd[14] = (track_center_y) & 0xFF + + begin_track_cmd[15] = (track_width >> 8) & 0xFF + begin_track_cmd[16] = (track_width) & 0xFF + + begin_track_cmd[17] = (track_height >> 8) & 0xFF + begin_track_cmd[18] = (track_height) & 0xFF + + begin_track_cmd[19] = 0 + begin_track_cmd[20] = 1 + + send_msg(begin_track_cmd) + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: tracking rectangle ON") +end + +-- check for changes in tracking state and send messages to gimbal if required +function check_tracking_state() + + -- get latest camera state from AP driver + local cam_state = camera:get_state(CAMERA_INSTANCE) + if not cam_state then + return + end + + -- check for change in tracking state + local tracking_type_changed = cam_state:tracking_type() ~= last_tracking_type + local tracking_type_p1_changed = (cam_state:tracking_p1():x() ~= last_tracking_p1x) or (cam_state:tracking_p1():y() ~= last_tracking_p1y) + local tracking_type_p2_changed = (cam_state:tracking_p2():x() ~= last_tracking_p2x) or (cam_state:tracking_p2():y() ~= last_tracking_p2y) + + + last_tracking_type = cam_state:tracking_type() + last_tracking_p1x = cam_state:tracking_p1():x() + last_tracking_p1y = cam_state:tracking_p1():y() + last_tracking_p2x = cam_state:tracking_p2():x() + last_tracking_p2y = cam_state:tracking_p2():y() + + if (last_tracking_type == 0) and tracking_type_changed then + -- turn off tracking + local stop_track_cmd = {35, 84, 80, 85, 68, 50, 119, 84, 82, 67, 48, 49} + send_msg(stop_track_cmd) -- stop track + is_tracking = false + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: tracking OFF") + end + + if (last_tracking_type == 1) and (tracking_type_changed or tracking_type_p1_changed) then + -- turn tracking point on + track_point(last_tracking_p1x, last_tracking_p1y) + is_tracking = true + end + + if (last_tracking_type == 2) and (tracking_type_changed or tracking_type_p1_changed or tracking_type_p2_changed) then + -- turn tracking rectangle on + tracking_rect(last_tracking_p1x, last_tracking_p1y, last_tracking_p2x, last_tracking_p2y) + is_tracking = true + end +end + +-- get information form gimbal +function get_gimbal_info() + if send_count%5 == 0 then + -- request memory card information within the specified time + local get_gimbal_sdcard_info = {35, 84, 80, 85, 68, 50, 114, 83, 68, 67, 48, 48} + send_msg(get_gimbal_sdcard_info) -- get gimbal memory card information + + -- if trace mode is enabled, trace status information is requested within a specified period of time + if is_tracking then + local get_gimbal_track_status = {35, 84, 80, 85, 68, 50, 114, 84, 82, 67, 48, 48} + send_msg(get_gimbal_track_status) -- get gimbal tracking status + end + end + + -- the gimbal attitude is obtained every second, and the gimbal will continue to send attitude information during the next period + if send_count%100 == 0 then + local get_gimbal_attitude = {35, 84, 80, 85, 71, 50, 119, 71, 65, 65, 48, 49} + send_msg(get_gimbal_attitude) -- get gimbal attitude + send_count = 0; + end + send_count = send_count + 1 +end + +-- initialize internal parameters. +function init_value() + -- get picture-in-picture mode + cam_pip_status = rc:get_aux_cached(CAM_PIP_RC_OPTION) + + -- set char_map + for i = 0, 9 do + char_map[i] = i + 48 + end + + for i = 10, 15 do + char_map[i] = i + 55 + end + + -- set number_map + for i = 0, 9 do + number_map[i + 48] = i + end + + for i = 97, 102 do + number_map[i] = (i - 87) + end + + for i = 65, 70 do + number_map[i] = (i - 55) + end +end + +-- find and initialise serial port connected to gimbal +function init() + -- check mount parameter + if MNT1_TYPE:get() ~= 9 then + gcs:send_text(MAV_SEVERITY.CRITICAL, "Topotek: set MNT1_TYPE=9") + do return end + end + + -- check cam type parametr + if CAM1_TYPE:get() ~= 7 then + gcs:send_text(MAV_SEVERITY.CRITICAL, "Topotek: set CAM1_TYPE=7") + do return end + end + + -- find and init first instance of SERIALx_PROTOCOL = 28 (Scripting) + uart = serial:find_serial(0) + if uart == nil then + gcs:send_text(3, "Topotek: no SERIALx_PROTOCOL = 28") -- MAV_SEVERITY_ERR + else + uart:begin(115200) + uart:set_flow_control(0) + initialised = true + gcs:send_text(MAV_SEVERITY.INFO, "Topotek: started") + end + + -- initialize internal parameters. + init_value() +end + +function update() + + -- initialise connection to gimbal + if not initialised then + init() + return update, INIT_INTERVAL_MS + end + -- consume incoming bytes + read_incoming_packets() + + -- send stop commands twice to prevent the gimbal from not receiving the command + repeat_stop_cmd() + + -- check camera state and send control messages + check_camera_state() + + -- check tracking state and send tracking control messages + check_tracking_state() + + -- get information form gimbal + get_gimbal_info() + + -- send target angle to gimbal + local roll_deg, pitch_deg, yaw_deg, deg_yaw_is_ef = mount:get_angle_target(MOUNT_INSTANCE) + + if roll_deg and pitch_deg and yaw_deg then + + -- set whether the gimbal is locked or followed command + set_gimbal_lock(deg_yaw_is_ef) + send_target_angles(roll_deg, pitch_deg, yaw_deg) + return update, UPDATE_INTERVAL_MS + end + + -- send target rate to gimbal + local roll_degs, pitch_degs, yaw_degs, degs_yaw_is_ef = mount:get_rate_target(MOUNT_INSTANCE) + + if roll_degs and pitch_degs and yaw_degs then + -- set whether the gimbal is locked or followed command + set_gimbal_lock(degs_yaw_is_ef) + send_target_rates(roll_degs, pitch_degs, yaw_degs) + return update, UPDATE_INTERVAL_MS + end + + return update, UPDATE_INTERVAL_MS +end + +return update() diff --git a/libraries/AP_Scripting/drivers/mount-topotek-driver.md b/libraries/AP_Scripting/drivers/mount-topotek-driver.md new file mode 100755 index 00000000000000..d6608ac005516b --- /dev/null +++ b/libraries/AP_Scripting/drivers/mount-topotek-driver.md @@ -0,0 +1,19 @@ +# Mount Topotek Driver + +Topotek gimbal driver lua script + +# How to use + + Connect gimbal UART to one of the autopilot's serial ports + Set SERIALx_PROTOCOL = 28 (Scripting) where "x" corresponds to the serial port connected to the gimbal + Set SERIALx_BAUD = 115 (115200) + Set SCR_ENABLE = 1 to enable scripting and reboot the autopilot + Set MNT1_TYPE = 9 (Scripting) to enable the mount/gimbal scripting driver + Set CAM1_TYPE = 7 (Scripting) to enable the camera scripting driver + Set RCx_OPTION = 300 (Scripting1) to control which camera's picture-in-picture mode. + Set SCR_HEAP_SIZE = 120000 + Copy this script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot + Set MNT1_RC_RATE to 90 (deg/s) to control gimbal movement. + Optionally set TOPK_DEBUG = 1 or 2 to increase level of debug output to the GCS + Reboot the autopilot +