From 8746d191f9c91e05097e71c756f87d19925f0f0a Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Tue, 25 Nov 2025 20:53:50 +0100 Subject: [PATCH 1/6] Quickshots Quickshots --- .../examples/FlyViewMavlinkActions.json | 37 ++ .../AP_Scripting/examples/QuickShots.lua | 431 ++++++++++++++++++ libraries/AP_Scripting/examples/Quickshots.md | 47 ++ 3 files changed, 515 insertions(+) create mode 100644 libraries/AP_Scripting/examples/FlyViewMavlinkActions.json create mode 100644 libraries/AP_Scripting/examples/QuickShots.lua create mode 100644 libraries/AP_Scripting/examples/Quickshots.md diff --git a/libraries/AP_Scripting/examples/FlyViewMavlinkActions.json b/libraries/AP_Scripting/examples/FlyViewMavlinkActions.json new file mode 100644 index 0000000000000..14b9df01b50d2 --- /dev/null +++ b/libraries/AP_Scripting/examples/FlyViewMavlinkActions.json @@ -0,0 +1,37 @@ +{ + "version": 1, + "fileType": "MavlinkActions", + "actions": +[ +{ + "label": "Dronie", + "description": "Dronie Mission", + "mavCmd": 31010, + "param1": 1, + "param2": 50, + "param3": 30, + "param4": 8, + "param5": 1 +}, +{ + "label": "Rocket", + "description": "Rocket Mission", + "mavCmd": 31010, + "param1": 2, + "param2": 0, + "param3": 30, + "param4": 8, + "param5": 1 +}, +{ + "label": "Helix", + "description": "Helix Mission", + "mavCmd": 31010, + "param1": 3, + "param2": 50, + "param3": 30, + "param4": 8, + "param5": 1 +} +] +} diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua new file mode 100644 index 0000000000000..e7cdd3ac0fa37 --- /dev/null +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -0,0 +1,431 @@ +-- Copter QuickShots +-- Dronie, Rocket, Helix +-- +-- triggered by MAVLink MAV_CMD_USER_1 (31010) +-- param1 QuickShot(1-Dronie, 2-Rocket, 3-Helix) +-- param2 max distance +-- param3 max altitude +-- param4 ROI distance +-- param5 start Mission +-- +-- QGC MavlinkActions +-- ~\Documents\QGroundControl\MavlinkActions\FlyViewMavlinkActions.json + +local maxDistance = 50 +local maxAltitude = 30 +local roiDistance = 8 +local startMission = 0 +local startAltitude = 4 +local sdDistance = 5 +local roiWP +local bearing +local gcs_location = Location() +local stage = 0 +local cmdQuickShot + +local mavlink_msgs = require("MAVLink/mavlink_msgs") + +local COMMAND_ACK_ID = mavlink_msgs.get_msgid("COMMAND_ACK") +local COMMAND_LONG_ID = mavlink_msgs.get_msgid("COMMAND_LONG") +local GLOBAL_POSITION_INT_ID = mavlink_msgs.get_msgid("GLOBAL_POSITION_INT") + +local msg_map = {} +msg_map[COMMAND_ACK_ID] = "COMMAND_ACK" +msg_map[COMMAND_LONG_ID] = "COMMAND_LONG" +msg_map[GLOBAL_POSITION_INT_ID] = "GLOBAL_POSITION_INT" + +-- initialize MAVLink rx with buffer depth and number of messages +mavlink:init(2, 2) + +-- register message id to receive +mavlink:register_rx_msgid(COMMAND_LONG_ID) +mavlink:register_rx_msgid(GLOBAL_POSITION_INT_ID) + +local MAV_COMP_ID_MISSIONPLANNER = 190 +local MAV_CMD_USER_1_ID = 31010 + +-- Block AP parsing MAV_CMD_USER_1 so we can deal with it in the script +-- Prevents "unsupported" ack +mavlink:block_command(MAV_CMD_USER_1_ID) + +function handle_command_long(cmd) + --gcs:send_text(6, string.format("COMMAND_LONG <%d/%d> %d", cmd.sysid, cmd.target_component, cmd.command) ) + + local ret = 0 + + if cmd.command == MAV_CMD_USER_1_ID then + gcs:send_text(6, string.format("MAV_CMD_USER_1_ID %d %d %d %d", cmd.param1, cmd.param2, cmd.param3, cmd.param4) ) + if cmd.param1 < 1 or cmd.param1 > 3 then + gcs:send_text(0, string.format("Quick Shot %d not implemented", cmd.param1)) + ret = 4 + end + if stage ~= 0 then + gcs:send_text(0, "still running") + ret = 4 + end + if arming:is_armed() then + gcs:send_text(0, "disarm first") + ret = 4 + end + if not ahrs:home_is_set() then + gcs:send_text(0, "waiting for gps") + ret = 4 + end + if ret == 0 then + cmdQuickShot = cmd.param1 + maxDistance = cmd.param2 + maxAltitude = cmd.param3 + roiDistance = cmd.param4 + startMission = cmd.param5 + stage = 1 + end + end + + return ret +end + +function handle_global_position_int(msg) + --gcs:send_text(6, string.format("position<%d.%d> %f %f %d", msg.sysid, msg.compid, msg.lat/1e7, msg.lon/1e7, msg.relative_alt/1000) ) + if msg.compid == MAV_COMP_ID_MISSIONPLANNER then + gcs_location:lat(msg.lat) + gcs_location:lng(msg.lon) + gcs_location:alt(msg.relative_alt / 10) + gcs_location:relative_alt(true) + end +end + +function calcWps() + startWp = ahrs:get_position() + if not startWp then + gcs:send_text(6, "ahrs:get_position() null") + end + + --gcs:send_text(6, string.format("gcs_location %f %f %d", gcs_location:lat()/1e7, gcs_location:lng()/1e7, gcs_location:alt()/1000) ) + if gcs_location:lat() ~= 0 then -- got gcs location + gcs:send_text(6, "got gcs location") + roiWP = gcs_location:copy() + bearing = math.deg(roiWP:get_bearing(startWp)) + else + gcs:send_text(6, "no gcs location, estimate roi") + bearing = 180 + math.deg(ahrs:get_yaw()) + roiWP = startWp:copy() + roiWP:offset_bearing(bearing, -roiDistance) + end + roiWP:alt(100) + + gcs:send_text(6, "waypoints calculated") + stage = 2 +end + +function createRocket() + local sdAltitude = 6 + + local rocketWP = startWp:copy() + rocketWP:alt(100 * maxAltitude) + local sldWP = startWp:copy() + sldWP:alt(100 * sdAltitude) + + local FRAME_GLOBAL_RELATIVE_ALT = 3 + + mission:clear() + + --WP0 is always home + local homeWP = ahrs:get_home() + local home = mavlink_mission_item_int_t() + home:seq(0) + home:frame(FRAME_GLOBAL_RELATIVE_ALT) + home:command(16) -- WP + home:x(homeWP:lat()) + home:y(homeWP:lng()) + home:z(homeWP:alt() / 100) + mission:set_item(0, home) + + -- Takeoff + local to = mavlink_mission_item_int_t() + to:seq(1) + to:frame(FRAME_GLOBAL_RELATIVE_ALT) + to:command(22) -- TAKEOFF + to:z(startAltitude) + mission:set_item(1, to) + + -- ROI + local wp = mavlink_mission_item_int_t() + wp:seq(2) + wp:frame(FRAME_GLOBAL_RELATIVE_ALT) + wp:command(201) -- SET_ROI + wp:x(roiWP:lat()) + wp:y(roiWP:lng()) + wp:z(roiWP:alt() / 100) + mission:set_item(2, wp) + + -- Rocket + wp:seq(3) + wp:command(16) -- WP + wp:x(0) + wp:y(0) + wp:z(rocketWP:alt() / 100) + mission:set_item(3, wp) + + -- Slow down + wp:seq(4) + wp:frame(FRAME_GLOBAL_RELATIVE_ALT) + wp:z(sldWP:alt() / 100) + mission:set_item(4, wp) + + -- Change Vertical Speed to 1m/s + local cs = mavlink_mission_item_int_t() + cs:seq(5) + cs:frame(FRAME_GLOBAL_RELATIVE_ALT) + cs:command(178) -- CHANGE_SPEED + cs:param1(3) -- down + cs:param2(1) + mission:set_item(5, cs) + + -- start + wp:seq(6) + wp:z(startAltitude) + mission:set_item(6, wp) + + -- land + local land = mavlink_mission_item_int_t() + land:seq(7) + land:frame(FRAME_GLOBAL_RELATIVE_ALT) + land:command(21) -- LAND + mission:set_item(7, land) + + gcs:send_text(0, "Rocket mission written") +end + +function createHelix() + local homeWP = ahrs:get_home() + + local wp = startWp:copy() + wp:alt(100 * startAltitude) + + local FRAME_GLOBAL_RELATIVE_ALT = 3 + local itemIdx = 0 + + mission:clear() + + --WP0 is always home + local m = mavlink_mission_item_int_t() + m:seq(itemIdx) + m:frame(FRAME_GLOBAL_RELATIVE_ALT) + m:command(16) -- WP + m:x(homeWP:lat()) + m:y(homeWP:lng()) + m:z(homeWP:alt() / 100) + mission:set_item(itemIdx, m) + itemIdx = itemIdx + 1 + + -- Takeoff + m:seq(itemIdx) + m:command(22) -- TAKEOFF + m:z(startAltitude) + mission:set_item(itemIdx, m) + itemIdx = itemIdx + 1 + + -- ROI + m:seq(itemIdx) + m:command(201) -- SET_ROI + m:x(roiWP:lat()) + m:y(roiWP:lng()) + m:z(roiWP:alt() / 100) + mission:set_item(itemIdx, m) + itemIdx = itemIdx + 1 + + local startRadius = roiDistance + local radius = startRadius + local alt = startAltitude + local wp_per_cycle = 20 + local radius_inc = (maxDistance - startRadius) / (wp_per_cycle - 1) + local alt_inc = (maxAltitude - startAltitude) / (wp_per_cycle - 1) + + while true do + bearing = bearing + 360 / (wp_per_cycle-1) + if bearing > 360 then + bearing = bearing - 360 + end + radius = radius + radius_inc + alt = alt + alt_inc + wp = roiWP:copy() + wp:offset_bearing(bearing, radius) + local distance = wp:get_distance(roiWP) + if (alt-maxAltitude) > 0.10 or (distance-maxDistance) > 0.10 then + break + end + m:seq(itemIdx) + m:command(16) -- 16 WP + m:x(wp:lat()) + m:y(wp:lng()) + m:z(alt) + mission:set_item(itemIdx, m) + itemIdx = itemIdx + 1 + end + + -- start + m:seq(itemIdx) + m:command(16) -- WP + local lat = startWp:lat() + local lng = startWp:lng() + m:x(lat) + m:y(lng) + m:z(startAltitude) + mission:set_item(itemIdx, m) + itemIdx = itemIdx + 1 + + -- land + m:seq(itemIdx) + m:command(21) -- LAND + m:x(0) + m:y(0) + m:z(0) + mission:set_item(itemIdx, m) + + gcs:send_text(0, "Helix mission written") +end + +function createDronie() + local FRAME_GLOBAL_RELATIVE_ALT = 3 + + local dronieWP = startWp:copy() + dronieWP:offset_bearing(bearing, maxDistance) + dronieWP:alt(100 * maxAltitude) + + local sdAlt = sdDistance * (maxAltitude - startAltitude) / maxDistance + startAltitude + local sldWP = startWp:copy() + sldWP:offset_bearing(bearing, sdDistance) + sldWP:alt(100 * sdAlt) + + mission:clear() + + --WP0 is always home + local homeWP = ahrs:get_home() + local home = mavlink_mission_item_int_t() + home:seq(0) + home:frame(FRAME_GLOBAL_RELATIVE_ALT) + home:command(16) -- WP + home:x(homeWP:lat()) + home:y(homeWP:lng()) + home:z(homeWP:alt() / 100) + mission:set_item(0, home) + + -- Takeoff + local to = mavlink_mission_item_int_t() + to:seq(1) + to:frame(FRAME_GLOBAL_RELATIVE_ALT) + to:command(22) -- TAKEOFF + to:z(startAltitude) + mission:set_item(1, to) + + -- ROI + local wp = mavlink_mission_item_int_t() + wp:seq(2) + wp:frame(FRAME_GLOBAL_RELATIVE_ALT) + wp:command(201) -- SET_ROI + wp:x(roiWP:lat()) + wp:y(roiWP:lng()) + wp:z(roiWP:alt() / 100) + mission:set_item(2, wp) + + -- Dronie + wp:seq(3) + wp:command(16) -- WP + wp:x(dronieWP:lat()) + wp:y(dronieWP:lng()) + wp:z(dronieWP:alt() / 100) + mission:set_item(3, wp) + + -- Slow down + wp:seq(4) + wp:frame(FRAME_GLOBAL_RELATIVE_ALT) + wp:x(sldWP:lat()) + wp:y(sldWP:lng()) + wp:z(sldWP:alt() / 100) + mission:set_item(4, wp) + + -- Change Speed to 1m/s + local cs = mavlink_mission_item_int_t() + cs:seq(5) + cs:frame(FRAME_GLOBAL_RELATIVE_ALT) + cs:command(178) -- CHANGE_SPEED + cs:param2(1) + mission:set_item(5, cs) + + -- start + wp:seq(6) + local lat = startWp:lat() + local lng = startWp:lng() + wp:x(lat) + wp:y(lng) + wp:z(startAltitude) + mission:set_item(6, wp) + + -- land + local land = mavlink_mission_item_int_t() + land:seq(7) + land:frame(FRAME_GLOBAL_RELATIVE_ALT) + land:command(21) -- LAND + mission:set_item(7, land) + + gcs:send_text(0, "Dronie mission written") +end + +function createMission() + if cmdQuickShot == 1 then + createDronie() + elseif cmdQuickShot == 2 then + createRocket() + elseif cmdQuickShot == 3 then + createHelix() + end + stage = 3 +end + +function runMission() + if startMission ~= 0 then + vehicle:set_mode(0) -- STABILIZE + arming:arm() + gcs:run_command_int(300, {}) -- Mission Start + end + stage = 0 +end + +function update() + local msg, chan = mavlink:receive_chan() + if msg then + local parsed_msg = mavlink_msgs.decode(msg, msg_map) + if parsed_msg then + local result + if parsed_msg.msgid == COMMAND_LONG_ID then + result = handle_command_long(parsed_msg) + elseif parsed_msg.msgid == GLOBAL_POSITION_INT_ID then + result = handle_global_position_int(parsed_msg) + end + if result then + -- Send ack if the command is one were interested in + local ack = {} + ack.command = parsed_msg.command + ack.result = result + ack.progress = 0 + ack.result_param2 = 0 + ack.target_system = parsed_msg.sysid + ack.target_component = parsed_msg.compid + mavlink:send_chan(chan, mavlink_msgs.encode("COMMAND_ACK", ack)) + end + end + end + + if stage == 1 then + calcWps() + elseif stage == 2 then + createMission() + elseif stage == 3 then + runMission() + end + + return update, 200 +end + +gcs:send_text(6, "QuickShots script starting") +return update, 100 diff --git a/libraries/AP_Scripting/examples/Quickshots.md b/libraries/AP_Scripting/examples/Quickshots.md new file mode 100644 index 0000000000000..5ceeb3ab7772d --- /dev/null +++ b/libraries/AP_Scripting/examples/Quickshots.md @@ -0,0 +1,47 @@ +# QuickShots for Copter +Script creates a Dronie, Rocket or Helix mission. +This is triggered by QGroundControl custom actions. + +# INSTRUCTIONS + +-setup scripting: +``` +SCR_ENABLE 1 +``` +- Use MP config tab -> MAVFtp to to copy the following scripts to the sd card +- 'libraries/AP_Scripting/examples/Quickshots.lua APM/scripts +- 'libraries/AP_Scripting/modules/MAVLink/mavlink_msgs.lua APM/scripts/modules/MAVLink +- 'libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_ACK.lua APM/scripts/modules/MAVLink +- 'libraries/AP_Scripting/modules/MAVLink/mavlink_msg_COMMAND_LONG.lua APM/scripts/modules/MAVLink +- 'libraries/AP_Scripting/modules/MAVLink/mavlink_msg_GLOBAL_POSITION_INT.lua APM/scripts/modules/MAVLink + +- Reboot + +-setup QGroundControl: +``` +Install QGroundControl 5.0 or higher +``` + +Place the file FlyViewMavlinkActions.json into the MavlinkActions directory +Windows: ~/Documents/QGroundControl/MavlinkActions +Android: /QGroundControl/MavlinkActions + +# USAGE + +Connect QGroundControl and wait for gps fix. +Create a mission via custom action. +Start the mission. +If param5 is set to 1 in FlyViewMavlinkActions.json the mission is started automatically. + +-ROI +If QGroundControl streams its position it is used as ROI. +Set "Stream GCS Position" to "always" in Application Settings for this to work. +If QGroundControl does not stream its position it is assumed the ROI (you) is 8m +in front of the drone, so place the drone 8m away facing you. + +# HOW IT WORKS + +The script waits for MAVLink message MAV_CMD_USER_1 (31010). +This message is sent from QGroundControl via custom action. +Depending on the parameters a Dronie, Rocket or Helix mission is created. +The GCS position is read if the GCS sends GLOBAL_POSITION_INT messages. From 16543351540429e5b5796fefb4e1d16c262ad21c Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Sun, 30 Nov 2025 08:05:15 +0100 Subject: [PATCH 2/6] Update QuickShots.lua --- libraries/AP_Scripting/examples/QuickShots.lua | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua index e7cdd3ac0fa37..1bf3ca1fc9262 100644 --- a/libraries/AP_Scripting/examples/QuickShots.lua +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -98,6 +98,7 @@ function calcWps() startWp = ahrs:get_position() if not startWp then gcs:send_text(6, "ahrs:get_position() null") + return end --gcs:send_text(6, string.format("gcs_location %f %f %d", gcs_location:lat()/1e7, gcs_location:lng()/1e7, gcs_location:alt()/1000) ) @@ -107,7 +108,7 @@ function calcWps() bearing = math.deg(roiWP:get_bearing(startWp)) else gcs:send_text(6, "no gcs location, estimate roi") - bearing = 180 + math.deg(ahrs:get_yaw()) + bearing = 180 + math.deg(ahrs:get_yaw_rad()) roiWP = startWp:copy() roiWP:offset_bearing(bearing, -roiDistance) end From 61b4f2fa350ca47d0e73b1af0967ef7000120a41 Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Sun, 30 Nov 2025 08:20:11 +0100 Subject: [PATCH 3/6] fix tests --- libraries/AP_Scripting/examples/QuickShots.lua | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua index 1bf3ca1fc9262..02752c8763f70 100644 --- a/libraries/AP_Scripting/examples/QuickShots.lua +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -96,6 +96,7 @@ end function calcWps() startWp = ahrs:get_position() + if not startWp then gcs:send_text(6, "ahrs:get_position() null") return From 9034b3b68e6caf0b42c96bc819506f2a2838a44e Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Sun, 30 Nov 2025 08:30:31 +0100 Subject: [PATCH 4/6] AP_Scripting: Quickshots --- libraries/AP_Scripting/examples/QuickShots.lua | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua index 02752c8763f70..1bf3ca1fc9262 100644 --- a/libraries/AP_Scripting/examples/QuickShots.lua +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -96,7 +96,6 @@ end function calcWps() startWp = ahrs:get_position() - if not startWp then gcs:send_text(6, "ahrs:get_position() null") return From 3b92431f1ee66b2ec44277cf8dd7752a437ff8dc Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Sun, 30 Nov 2025 08:38:20 +0100 Subject: [PATCH 5/6] AP_Scripting: Quickshots --- libraries/AP_Scripting/examples/QuickShots.lua | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua index 1bf3ca1fc9262..02752c8763f70 100644 --- a/libraries/AP_Scripting/examples/QuickShots.lua +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -96,6 +96,7 @@ end function calcWps() startWp = ahrs:get_position() + if not startWp then gcs:send_text(6, "ahrs:get_position() null") return From 5580707b649fa41e9b32acf08d94f67f6bac9caf Mon Sep 17 00:00:00 2001 From: TwistedWings Date: Sun, 30 Nov 2025 09:35:19 +0100 Subject: [PATCH 6/6] AP_Scripting: Quickshots fix tests --- libraries/AP_Scripting/examples/QuickShots.lua | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_Scripting/examples/QuickShots.lua b/libraries/AP_Scripting/examples/QuickShots.lua index 02752c8763f70..1bf3ca1fc9262 100644 --- a/libraries/AP_Scripting/examples/QuickShots.lua +++ b/libraries/AP_Scripting/examples/QuickShots.lua @@ -96,7 +96,6 @@ end function calcWps() startWp = ahrs:get_position() - if not startWp then gcs:send_text(6, "ahrs:get_position() null") return