Script to allow creating and looping a mission from the radio

Hello i’m triing to create a script to be triggered with an auxiliary radio channel,
the script should add a DO_JUMP mission command after the waypoints saved with the channel 7 switch (Save Waypoint).
I started to merge the code from this 2 example scripts:

i’m not very good at scripting but this is what i come up with so far:

– example of getting RC input

local scripting_rc_1 = rc:find_channel_for_option(300)
local scripting_rc_2 = rc:find_channel_for_option(301)
local flip_flop = 0

function update()
pwm1 = rc:get_pwm(1)
pwm2 = rc:get_pwm(2)
pwm3 = rc:get_pwm(3)
pwm4 = rc:get_pwm(4)

– added code
current_pos = ahrs:get_position()

– adds new/extra mission item at the end by copying the last one and modifying it
– get number of last mission item
wp_num = mission:num_commands()-1
–get last item from mission
m = mission:get_item(wp_num)
– get first item from mission
m1 = mission:get_item(1)

– added end

– read switch input from second designated scripting RCx_OPTION
if scripting_rc_2 then
local sw_pos = scripting_rc_2:get_aux_switch_pos()
if sw_pos == 0 then
gcs:send_text(0, “Scripting switch is low”)
elseif sw_pos == 1 then
gcs:send_text(0, “Scripting switch is middle”)

–added code to inser a do jump
m:command(177) – 177 = DO_JUMP
m:param1(1) – some increments for fun/demo
m:param2(99)
gcs:send_text(0, string.format(“LUA new miss-item DO_JUMP”))
mission:set_item(mission:num_commands(),m)

else
  gcs:send_text(0, "Scripting switch is high")
end

end
end

return update()

i haven’t tested it yet, do you have any suggestion or see any error/missing part? will it work with ardurover 4.1rc1 or i must use the development version?

Thanks in advance, Nicola

The script will not work as written because it will exit upon the first call of update().

If you have any experience with Arduino or microcontroller code, consider the update() function as the void loop() method with a little catch - it has to reschedule itself to run. Here’s a short example:

function update()
    gcs:send_text(6, 'This message will be sent once per second.')
    return update, 1000  -- reschedules update() in 1000 ms
end

return update()

Also, the PWM values are not binary. They will vary between approximately 1000-2000 μs in value, depending on how the transmitter is set up.

I made a video on the subject if you have the time or inclination to watch. It’s probably a bit tedious, but I think you’d benefit from the concepts introduced there.

I might have a little time to work up an example that does what you want. I think this basic algorithm may help simplify the steps you likely need (you won’t need an RC input mapped to SaveWP to do this):

  1. Poll the RC channel for its PWM value.
  2. If that value is greater than 1500, and we haven’t already added a waypoint here, get the vehicle location
  3. If the current mission is empty:
    a. Store the location as a waypoint command in position 1
    b. Create a DO_JUMP command in position 2
  4. If there is an existing mission:
    a. Store the location as a waypoint command in the last command position (overwriting the DO_JUMP)
    b. Create a DO_JUMP command as the next command
  5. Set a wp_added variable to true to make sure we don’t continue adding waypoints while the switch is held high.
  6. If the switch’s PWM value is less than 1500, set wp_added to false
  7. Reschedule the function to run in 50-100 μs

I don’t see why this script won’t work in any 4.1.0 or 4.2.0 version. Scripting is supported in Copter/Rover 4.0 and greater (and Plane 3.11 and greater), and DO_JUMP has existed since at least 2013.

EDIT:
I see now that the get_aux_switch_pos() function does indeed return a binary value. I’ll have to experiment a little with that one since I’ve not used it before. Perhaps the PWM values are irrelevant when using that function.

thanks Yuri, I watched the video, nice and informative!
the script now detects the rc channel but i get this error when the i try to insert the DO_JUMP
#1 to 'get_item' (argument out of range)
i think i need to get the index of the last waypoint,
this is the code

– example of getting RC input

local scripting_rc_2 = rc:find_channel_for_option(300)
local flip_flop = 0

function update()
pwm1 = rc:get_pwm(1)
pwm2 = rc:get_pwm(2)
pwm3 = rc:get_pwm(3)
pwm4 = rc:get_pwm(4)
gcs:send_text(0, “RCIN 1:” … tostring(pwm1) … " 2:" … tostring(pwm2)… " 3:" … tostring(pwm3)… " 4:" … tostring(pwm4))

– wp_num = mission:num_commands()-1
– m = mission:get_item(wp_num)

– read switch input from second designated scripting RCx_OPTION
if scripting_rc_2 then
local sw_pos = scripting_rc_2:get_aux_switch_pos()
if sw_pos == 0 then
gcs:send_text(0, “Scripting switch is low”)
elseif sw_pos == 1 then
gcs:send_text(0, “Scripting switch is middle”)
else
gcs:send_text(0, “Scripting switch is high”)
return dojump(), 0

end

end

return update, 1000 – reschedules the loop
end

function dojump()

wp_num = mission:num_commands()-1
– get HOME item from mission as the ‘reference’ for future items
– m1 = mission:get_item(0)
–get last item from mission
m = 1
m:command(177) – 177 = DO_JUMP
m:param1(1) – some increments for fun/demo
m:param2(99)
gcs:send_text(0, “LUA new miss-item DO_JUMP”)
mission:set_item(mission:num_commands(),m)
end
return update()

Your script is failing because of the line m = 1. The way the example works, it grabs an existing waypoint from the mission table and uses that as a template. You commented that portion out.

I worked up this example for you and tested it via SITL. Because I don’t have a radio or joystick connected to the simulation, I’m detecting Loiter mode as the trigger to save the waypoint and add the DO_JUMP.

You’ll have to modify it slightly to detect your radio switch instead of executing on Loiter mode, but this should get you moving in the right direction.

local NUM_LOOPS =  99  -- number of times to repeat the mission
local FREQUENCY =  50  -- (ms) how often to run this script

local WAYPOINT  =  16
local DO_JUMP   = 177

local wp_added = false

function add_waypoint_here(wp_index)
    local wp = mission:get_item(0)  -- use HOME as a template
    local position = ahrs:get_position()
    
    if (not position) then
        return false
    end
    
    wp:command(WAYPOINT)
    wp:x(position:lat())
    wp:y(position:lng())
    wp:z(position:alt() * 0.01)  -- altitude decimal place needs to be moved for use in mission
    mission:set_item(wp_index, wp)
    
    return true
end

function add_jump(wp_index, jump_to_here, num_loops)
    local wp = mission:get_item(0)  -- use HOME as a template
    
    wp:command(DO_JUMP)
    wp:param1(jump_to_here)
    wp:param2(num_loops)
    mission:set_item(wp_index, wp)
end

function update()

    if (vehicle:get_mode() ~= 5) then  -- check for LOITER mode
        wp_added = false
        return update, FREQUENCY
    end
    
    if (wp_added) then
        return update, FREQUENCY
    end

    num_commands = mission:num_commands()

    if (num_commands < 2) then  -- don't overwrite HOME
        num_commands = 2
    end

    if (not add_waypoint_here(num_commands - 1)) then
        gcs:send_text(4, 'Invalid position, waypoint not saved')
        return update, FREQUENCY
    end
    
    add_jump(num_commands, 1, NUM_LOOPS)
    wp_added = true
    gcs:send_text(6, string.format('Waypoints %d and %d saved', num_commands - 1, num_commands))
    return update, FREQUENCY

end

return update()

got it working somehow!
If there are less then 2 waypoints it just wont add the dojump.
i have mapped save waypoint and clear waypoints to 2 aux channels.

here is the test code:

local scripting_rc_2 = rc:find_channel_for_option(300)

wp_num = 0
m = {}

function update()

if (mission:num_commands() > 2) then
wp_num = mission:num_commands()-1
end

– read switch input from second designated scripting RCx_OPTION
if scripting_rc_2 then
local sw_pos = scripting_rc_2:get_aux_switch_pos()
if sw_pos == 0 then
gcs:send_text(0, “Scripting switch is low”)
elseif sw_pos == 1 then
gcs:send_text(0, “Scripting switch is middle”)
else
gcs:send_text(0, “Scripting switch is high”)
m = mission:get_item(wp_num)
if (mission:num_commands() > 2) then
return dojump(), 500
end
end
end

return update, 1000 – reschedules the loop
end

function dojump()
m:command(177) – 177 = DO_JUMP
m:param1(1) – some increments for fun/demo
m:param2(99)
gcs:send_text(0, “LUA new miss-item DO_JUMP”)
mission:set_item(mission:num_commands(),m)

return update, 1000
end

return update()

i’m gonna test it in the water :slight_smile:

My example works regardless of the number of waypoints…

Tested and worked fine! oh the joy of programming looped missions with just the radio!!
Thanks again for your video and hints, it helped me a lot to undestand why it wasnt’ working
This lua scripting integration opens many doors of possiblities with ardupilot!
i’ll try your version too, but what you mean for regardless? what will do if i try to loop 1 waypoint? and what when 0 waypoints?
would be nice to be able to add/remove next waypoints in the mission by switching to manual/steeering/acro in the middle of the loop mission, triggering the rc switches to add/remove a waypoint, then switching back to auto to continue cycle the edited waypoints, like a radio based looped mission editor, but for now i’m already super happy with this archivement!
:fishing_pole_and_fish:

My example will behave as you want with 0, 1, or many waypoints.

Again, you’ll have to modify it to really use it. If you load it as is, you’ll have to enter Loiter mode each time you want to trigger it.

1 Like