Select Up to 9 Flight Modes on Non-Mixing Transmitters [SOLVED - Lua Script]

I needed a script to use a DJI Remote controller w/Arduplane as it has no ability to create mixes, etc. in the Tx.

This is a test file (need to finish putting in all the desired modes).
It seems to work (the gcs words are appearing in MP) but are there any glaring errors? Is the update time too short/long? Feedback would be very welcome. (TIA)


– script to use two channels to change mode in Arduplane –
– using channels 6 and 7 for mode selection (DJI Remote Controller –

local chan6Pwm = rc:find_channel_for_option(300) – input for the use of onboard lua scripting
local chan7Pwm = rc:find_channel_for_option(301)

function update()
pwm6 = rc:get_pwm(6)
pwm7 = rc:get_pwm(7)

if (pwm6 < 1300) then                                                 -- sw 6 up
    if (pwm7 < 1300) then                                             -- sw 6 up       sw 7 up
       vehicle:set_mode(0)
       gcs:send_text(0, "Manual mode")
       return update, 100 -- reschedules the loop
    elseif (pwm7 > 1300 and pwm7 < 1700) then   -- sw 6 up      sw 7 mid
       vehicle:set_mode(2)
       gcs:send_text(0, "Stabilize mode")
       return update, 100 -- reschedules the loop
    else                                                                                -- sw 6 up      sw 7 down
       vehicle:set_mode(10)
       gcs:send_text(0, "Waypoint mode")
       return update, 100 -- reschedules the loop
    end                                                                                 -- end  if sw 6 up
elseif (pwm6 > 1300 and pwm6< 1700) then                   -- sw 6 mid
    if (pwm7 < 1300) then                                             -- sw 6 mid      sw 7 up
       vehicle:set_mode(5)
       gcs:send_text(0, "FBWA mode")
       return update, 100 -- reschedules the loop
    elseif (pwm7 > 1300 and pwm7 < 1700) then    -- sw 6 mid      sw 7 mid
       vehicle:set_mode(8)
       gcs:send_text(0, "Autotune mode")
       return update, 100 -- reschedules the loop
    else                                                                                -- sw 6 mid     sw 7 down
       vehicle:set_mode(12)
       gcs:send_text(0, "Loiter mode")
       return update, 100 -- reschedules the loop
    end                                                                                -- end  if sw 6 mid
elseif (pwm6 > 1700) then                                         -- sw 6 down
    if (pwm7 < 1300) then                                             -- sw 6 down      sw 7 up
       --  vehicle:set_mode(5)
       gcs:send_text(0, "6dn 7 dn mode")
       return update, 100 -- reschedules the loop
    elseif (pwm7 > 1300 and pwm7 < 1700) then    -- sw 6 down   sw 7 mid
       -- vehicle:set_mode(8)
       gcs:send_text(0, "6 dn 7mid mode")
       return update, 100 -- reschedules the loop
    else                                                                                -- sw 6 down   sw 7 down
       vehicle:set_mode(11)
       gcs:send_text(0, "RTL mode")
       return update, 100 -- reschedules the loop
    end                                                                               -- if sw 6 is down
end  -- end if block

end – func update()

return update()

1 Like

You never use the awkwardly named chan6pwm and chan7pwm objects. Instead, you poll the channels directly. Those objects will return 0, 1, or 2 when you call their get_aux_switch_pos() methods.

Your script would be more robust if you used those objects and their methods, and then the specific channels would not need to be hard coded (instead the 300 and 301 values are used to “find” those channels).

The 0 argument in your gcs:send_text() calls indicates a malfunction of utmost severity based on the MAVLink standard. You should use a value of 6 to adhere to the standard or 4 if you want to raise the severity enough that Mission Planner will read it aloud.

As for coding practice, multiple layers of if/then/else statements should usually be broken up into functions or simpler conditional statements. It’s harder to follow and maintain deeply nested logic. It’s possible that there’s a condition you haven’t accounted for that will cause your script to simply exit since there is no return statement after the long nested conditionals.

I think I just noticed as well that the script will continue to set and reset the mode as long as a given condition is true. You should probably only trigger a mode change when the switch position changes.

Yuri,
thanks SO MUCH! Guess I should have taken programming classes at school :slight_smile:

I didn’t think lua had a switch so just did the nested ifs. I did notice the messages continue pumping in MP … didn’t think of your great idea to just check to see if a switch has been moved. Was totally unaware of 0 in the gcs statement - new it meant something but couldn’t find out what! Guess I’ll start w/the manual at lua.org first. I assume other items like rc:find_channel_for_option(300) are somewhere on GitHub.

Thanks again for your helpful critique!

You’re welcome. I was typing from my phone earlier so it was hard to provide links. The Lua foundation has really good documentation, but it does not address the idiosyncrasies of Lua for ArduPilot.

I’m afraid that rc:find_channel_for_option(300) and :get_aux_switch_pos() aren’t well documented, either. Look through the examples on GitHub to get a feel for how they work. It would look something like:

local FREQUENCY = 100
local RC_OPTION = 300

local aux_sw = rc:find_channel_for_option(RC_OPTION)

function update()
    sw_pos = aux_sw:get_aux_switch_pos()
    if sw_pos == 0 then
            --do logic
            return update, FREQUENCY
    end
    if sw_pos == 1 then
            --do other logic
            return update, FREQUENCY
    end
    if sw_pos == 2 then
            --do other, other logic
            return update, FREQUENCY
    end
    return update, FREQUENCY
end

Lua does not have a switch/case statement. Your use of early return calls is good practice (note that I didn’t even bother with else or elseif in my example). You might consider crafting a couple of functions to break up the conditional logic. Good function names would help keep track of what is happening in the code.

Here is the MAVLink severity message documentation.

If you have a half hour to kill, I made a video on scripting for ArduPilot.

1 Like

I’ve just found GitHub ArduPilot/libraries and lua script documentation in Ardupilot so I think I can make sense of it all,
Little things like return update, #### are hard to find out what values should be used and just how it works. etc.
Very Good Video!
Thanks again Yuri - Have a nice holiday!

2 Likes

tested this version in flight - it worked!
Changed it a bit so it only does the if’s if a mode switch has been used
I’m sure there must be an easier way to check if a switch has moved but I got tired of looking.
Did try 7 flight modes and all worked. I normally only use 5 but I could use more when flying quadplanes …


– script to use two channels to change mode in Arduplane –
– using channels 6 and 7 for mode selection (DJI Remote Controller ) –

local lastPosition = 0  -- used to comnpare if any changes made
local newPosition = 0

local tempPosition = rc:get_pwm(6)  -- get PWM of channel 6, low is 1000, high 2000, and middle is 1500
if tempPosition < 1300 then   -- in low position
    lastPosition = 1
elseif tempPosition > 1300 and tempPosition < 1700 then
   lastPosition = 2
else  lastPosition = 3
end

local tempPosition =  rc:get_pwm(7)
if tempPosition < 1300 then
    lastPosition = lastPosition + 10
elseif tempPosition > 1300 and tempPosition < 1700 then
   lastPosition = lastPosition + 20
else  lastPosition = lastPosition  + 30
end

function update()
local newPosition – used to compare if either switch moved
pwm6 = rc:get_pwm(6) —pwm for channel 6
pwm7 = rc:get_pwm(7)

if pwm6 < 1300 then
    newPosition = 1
elseif pwm6 > 1300 and pwm6  < 1700 then
   newPosition = 2
else  newPosition = 3
end

if pwm7 < 1300 then
    newPosition = newPosition + 10
elseif pwm7 > 1300 and pwm7  < 1700 then
   newPosition = newPosition + 20
else  newPosition = newPosition +30
end

if ( rc:find_channel_for_option(301) or rc:find_channel_for_option(300) ) then      --  something changed
    lastPosition = newPosition -- update so it doesn't repeat until another change occurs

    if (pwm6 < 1300) then                                                 -- sw 6 up position (low pwm for the DJI)
        if (pwm7 < 1300) then                                             -- sw 6 up       sw 7 up
           vehicle:set_mode(0)
           gcs:send_text(6, "Manual mode")
           return update, 500 -- reschedules the loop
        elseif (pwm7 > 1300 and pwm7 < 1700) then   -- sw 6 up      sw 7 mid
           vehicle:set_mode(5)
           gcs:send_text(6, "FBWA mode")
           return update, 500 -- reschedules the loop
        else                                                                                 -- sw 6 up      sw 7 down
           vehicle:set_mode(2)
           gcs:send_text(6, "Stabilized mode")
           return update, 500 -- reschedules the loop
        end                                                                                 -- end  if sw 6 up
        --------------------------------------------------------------------------------
    elseif (pwm6 > 1300 and pwm6< 1700) then       -- sw 6 mid
        if (pwm7 < 1300) then                                             -- sw 6 mid      sw 7 up
           --  vehicle:set_mode(5)
           gcs:send_text(6, "no mode")
           return update, 500 -- reschedules the loop
        elseif (pwm7 > 1300 and pwm7 < 1700) then    -- sw 6 mid      sw 7 mid
           --  vehicle:set_mode(13)
           gcs:send_text(6, "no mode")
           return update, 500 -- reschedules the loop
        else                                                                                 -- sw 6 mid       sw 7 down
           --  vehicle:set_mode(12)
           gcs:send_text(6, "no mode")
           return update, 500 -- reschedules the loop
        end                                                                                 -- end  if sw 6 mid
        --------------------------------------------------------------------------------
    elseif (pwm6 > 1700) then                                         -- sw 6 down
        if (pwm7 < 1300) then                                             -- sw 6 down      sw 7 up
           vehicle:set_mode(10)
           gcs:send_text(6, "Waypoint mode")
           return update, 500 -- reschedules the loop
        elseif (pwm7 > 1300 and pwm7 < 1700) then    -- sw 6 down   sw 7 mid
          vehicle:set_mode(12)
           gcs:send_text(6, "Loiter mode")
           return update, 500 -- reschedules the loop
        else                                                                                -- sw 6 down    sw 7 down
           vehicle:set_mode(11)
           gcs:send_text(6, "RTL mode")
           return update, 500 -- reschedules the loop
        end                                                                                -- if sw 6 is down
        --------------------------------------------------------------------------------
    end  -- end if block
end   -- if a switch position changed
    return update, 500 -- reschedules the loop

end – function update

return update, 500

You’re still not making use of the find channel and aux position functions in any meaningful way.

It might be better to use a lookup table for your modes.

If you watched my video, the example using a state machine type architecture is a means to keep track of switch position without explicitly assigning and comparing a variable.

1 Like

Thanks! I’ll watch it again later tonight

Alternatively, you can just check if vehicle mode needs to change before the set_mode() call.

thanks, it would be nice if all these options, and how they’re used was summarized but it would take a lot of work and be a bear to maintain I suppose…

I’ve seen more than one post here regarding the use of Lua to overcome the lack of mixing on transmitters like DJI and HereLink, so rather than continuing to give you code snippets, hints, and tips, I wrote a more fully featured script that should be useful to the community.

While your script should work fine, it will likely live only on your vehicle, and it’s honestly a little difficult to maintain or modify, given the nested logic and lack of variable naming convention.

If you’d be willing to give my script a try, I’d appreciate feedback as to how it works for you. I think I captured the flight modes you’re using based on the logic in your own script. You’ll have to set RC6_OPTION=300 and RC7_OPTION=301 for your particular transmitter setup.

If it suits your needs, perhaps we will rename the thread title for others to find it as well.

The script I wrote is hosted in my GitHub repository and uses tables to map the modes and switch positions in a way that I hope is very readable.

While my script appears twice the length of yours, if you remove all of the commented lines and white space, it’s actually a bit more compact with less conditional logic (but a bit more memory devoted to variable storage).

At its core, the update() function is reduced to the following, where set_vehicle_mode() is a locally defined function that checks whether it’s actually necessary to call vehicle:set_mode():

function update()
    local sw1_pos = aux_sw_1:get_aux_switch_pos()
    local sw2_pos = aux_sw_2:get_aux_switch_pos()

    if sw1_pos == last_sw1_pos and sw2_pos == last_sw2_pos then
        return update, FREQUENCY
    end

    set_vehicle_mode(MODE_MAP[sw1_pos][sw2_pos])
    last_sw1_pos = sw1_pos
    last_sw2_pos = sw2_pos

    return update, FREQUENCY
end

As for your comment about a summary of all functions, methods, and variables available within the ArduPilot Lua sandbox, the following two links are invaluable references:

Binding generator descriptions
Binding generator auto-generated documentation

1 Like

That’s certainly some robust code! I even understand a lot of it.
Will try to test it this weekend… have a front moving through so it’s rather windy right now…

1 Like

Did a quick bench test. I’m going to have to do a methodical check to make sure its working properly. It seemed if I change ch 6 then 7, it worked as advertised but if I change 7 then 6, I would get erroneous results. Again, I could be wrong so I need to make a chart and try each option and note the results and messages. Also I thought it was “skipping” sometimes until I changed the flight channel to 12 (an unused freq) and didn’t notice any problem. Hopefully I’ll have everything set up and give it a good walk-thru then test flight.

That seems like odd behavior for sure. It seemed to work well when I tested in SITL. Is there any other channel commanding flight modes?

If indeed you have found a bug, I will happily fix it before you fly.

I did fire up SITL one more time tonight, switched channels methodically, attempted to use every switch permutation, and I could not reproduce the “skip” behavior you experienced.

Before you fly, you may want to double check that the failsafe behavior is unaffected by the script in the event of transmitter signal loss. I did not test that.

here’s an Excel sheet of what I did
followed it from top to bottom
first section moved channel 6 then stepped through 7
second section moved 7 first then stepped thru 6
oops! wouldn’t allow me to upload the excel … here’s a picture …

I will attempt that exact sequence this weekend.

Of note, if the switch position is “UNASSIGNED,” the flight mode will remain in its previous state (I’m thinking this might account for your observed “skips”).

Also, most of your chart’s programmed response column is incorrect for the “7 then 6” series. For example, the expected response for 7 LOW / 6 MID is FBWA, not STABILIZE (which is 6 LOW / 7 MID).

Read the mode map in pseudo-columns like this:

   --RC6
    [LOW] = {
       --RC7
        [LOW]  = 'PLANE_MODE_MANUAL',
        [MID]  = 'PLANE_MODE_STABILIZE',
        [HIGH] = 'PLANE_MODE_AUTO'
    },
   --RC6
    [MID] = {
       --RC7
        [LOW]  = 'PLANE_MODE_FLY_BY_WIRE_A',
        [MID]  = 'PLANE_MODE_AUTOTUNE',
        [HIGH] = 'PLANE_MODE_LOITER'
    },
   --RC6
    [HIGH] = {
       --RC7
        [LOW]  = 'VEHICLE_MODE_UNASSIGNED',
        [MID]  = 'VEHICLE_MODE_UNASSIGNED',
        [HIGH] = 'PLANE_MODE_RTL'

Instead of leaving two of the RC6:HIGH modes unassigned, maybe we should assign them all to RTL. That way no matter what you do with RC7, if you go HIGH on RC6, you get RTL. That still leaves room for future flexibility if you want 8 or 9 modes, but there will never be a case where you get the UNASSIGNED/no mode switch behavior.

1 Like

Doh! Could blame it on it being late but I probably would have done that in the AM also …

So … w/the corrected chart it looks like it’s behaving as it’s supposed to.
Will upload and flight test it in an Albabird.

1 Like

Yuri !
Congratulations!

Your script worked perfectly! I even filled all nine options and they all worked.

Normally I only need 5 modes but can use more on my quadplanes.

This is a really handy script! I have lots of programmable radios but a number (Herelink, DJI Remote Controller, etc.) that could only offer 3 modes. Your script solved everything.

Thank You!

Any suggestions on renaming the thread to increase visibility?

P.S. I would mention in the pre-amble that the RC channel number option needs to be change in Mission Planner’s config. i.e. set RC6_OPTION to 300 if you want to use channel 6, etc. Might also mention to change the FLT_MODE channel to an unused channel just in case it could interfere. I set it to 12 which isn’t an option on the radio I used. I didn’t get a chance to check if it actually does interfere.

Really glad to hear it! I can push a minor update to the comment section.

To be clear, there wasn’t anything “wrong” with your approach. The logic was just somewhat hard to follow, and the coding style left more room for errors that you or I might not have caught before you flew.

As it happens, I have enough “trust” to modify titles, so I did just that. Let me know if you think there’s a better title.

1 Like

So just to be clear, using this script would allow for mixing controls for a Herelink (ground unit) controller?