Skip to content

Commit

Permalink
AP_Scripting: Add Heli_IM_COL_TUNE applet and readme
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear authored and tridge committed Sep 9, 2020
1 parent 39788aa commit 32de8d7
Show file tree
Hide file tree
Showing 2 changed files with 249 additions and 0 deletions.
172 changes: 172 additions & 0 deletions libraries/AP_Scripting/applets/Heli_IM_COL_Tune.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,172 @@
-- This script is a useful tool when first setting up a heli. You can use it to dial in the IM_STB_COL_2 and
-- IM_STAB_COL_3 parameters in a more intuative way. It is meant for use with a transmitter that has two pots
-- available. 1 Pot can be used to control the gradient of the line between the 40% and 60% curve points. Use
-- this pot to adjust the sensitivity of the collective about the collective midstick. The 2nd Pot then controls
-- the value of the 50% point on the curve. This can be used to set the collective position to aid with hovering
-- at the midstick.

-- Tested and working as of 25th Aug 2020 (Copter Dev)

function update()
local rcin_50 = col50_val_ch:norm_input_ignore_trim()
local rcin_grad = col_grad_ch:norm_input_ignore_trim()
rcin_save = save_switch_ch:get_aux_switch_pos()

-- Offset starting midstick curve value to get new value
-- Max = +30% , Min = -30%
local im_50 = (value_im_3 + value_im_2) * 0.5 --(%)
local delta_50 = rcin_50*30
im_50 = im_50 + delta_50

-- Scale rcin_grad to be between 0 and 1
rcin_grad = (rcin_grad+1)*0.5

-- Calculate delta due to gradient
local grad_40 = rcin_grad * -10 --(%)
local grad_60 = rcin_grad * 10 --(%)

-- Calculate param values
local im_40_pct = im_50+grad_40
local im_60_pct = im_50+grad_60

-- Ensure IM_STB_COL_2 < IM_STB_COL_3
if im_40_pct >= im_60_pct then
im_40_pct = im_60_pct - 1
end

-- Ensure IM_STB_COL_2 and IM_STB_COL_3 are withing appropriate ranges
im_40_pct = min_max(math.floor(im_40_pct),1,98)
im_60_pct = min_max(math.floor(im_60_pct),2,99)

-- Enforce that IM_STB_COL_1 < IM_STB_COL_2
local im_0_pct = get_im_val('IM_STB_COL_1',false)
if im_0_pct >= im_40_pct then
-- Correct within parameter limits
im_0_pct = min_max(im_40_pct - 1,0,97)

-- Set correct value to prevent pre-arm warnings
set_save_param('IM_STB_COL_1',im_0_pct,false)
end

-- Enforce that IM_STB_COL_4 > IM_STB_COL_3
im_100_pct = get_im_val('IM_STB_COL_4',false)
if im_100_pct <= im_60_pct then
-- Correct within parameter limits
im_100_pct = min_max(im_60_pct + 1,3,100)

-- Set correct value to prevent pre-arm warnings
set_save_param('IM_STB_COL_4',im_100_pct,false)
end

-- Save params only if switch active
if rcin_save < 1 then
-- just set 40% and 60% parameter values
set_save_param('IM_STB_COL_2',im_40_pct,false)
set_save_param('IM_STB_COL_3',im_60_pct,false)
else
set_save_param('IM_STB_COL_1',im_0_pct,true)
set_save_param('IM_STB_COL_2',im_40_pct,true)
set_save_param('IM_STB_COL_3',im_60_pct,true)
set_save_param('IM_STB_COL_4',im_100_pct,true)

-- Set script exit condition
script_status = COMPLETE
end

-- Reschedule
foo, sched = script_cont_stop()
return foo, sched
end


-- Get parameter value and perform checks to ensure successful
function get_im_val(param_name,disp)
local value = -1
value = param:get(param_name)

if value >= 0 then
if disp then
gcs:send_text(3, string.format('LUA: %s = %i',param_name,value))
end
else
gcs:send_text(3, string.format('LUA: Failed get %s',param_name))
script_status = false
end

return value
end


-- Prevent parameters from being set out of range
function min_max(value,min,max)
if value < min then
value = min
end

if value > max then
value = max
end

return value
end


-- Standardised function for stopping or continuing
function script_cont_stop()
if script_status == HEALTHY then
return update, 500

elseif script_status == COMPLETE then
gcs:send_text(2, 'LUA: IM_COL tune complete')

elseif script_status == NORC then
gcs:send_text(2, 'LUA: RC channels not set')

else --FAULT
gcs:send_text(2, 'LUA: IM_COL setter stopped')
end
end


-- function for setting and saving parameter
function set_save_param(str,val,save)
if save then
-- Set and save
if param:set_and_save(str,val) then
gcs:send_text(2, 'LUA: params saved')
else
gcs:send_text(2, 'LUA: param set failed')
end
else
-- Just set
if not(param:set(str,val)) then
gcs:send_text(2, 'LUA: param set failed')
end
end
end

--- -- -- Initial Setup --- --- ---
-- Script status levels
FAULT = 0
NORC = 1
HEALTHY = 2
COMPLETE = 3

script_status = HEALTHY

-- Set RC channels to use to control im_stb_col params
col50_val_ch = rc:find_channel_for_option(300) --scripting ch 1
col_grad_ch = rc:find_channel_for_option(301) --scripting ch 2
save_switch_ch = rc:find_channel_for_option(302) --scripting ch 3

if (col50_val_ch == nil or col_grad_ch == nil or save_switch_ch == nil) then
script_status = NORC
end

-- Get im_stb_col parameter values and store
value_im_2 = get_im_val('IM_STB_COL_2',true)
value_im_3 = get_im_val('IM_STB_COL_3',true)

-- Only continue running script if healthy
foo, sched = script_cont_stop()
return foo, sched
77 changes: 77 additions & 0 deletions libraries/AP_Scripting/applets/Heli_IM_Col_Tune.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
# Heli_IM_Col_Tune Lua Script

This is a useful tool when setting up a traditional heli. It is used to tune the `IM_STAB_COL_<X>` input curve. Typically, it is awkward to tune the `IM_STAB_COL_2` and `IM_STAB_COL_3` parameters to get the heli hovering around mid-stick with the desired finesse to maintain the hover, unless you have someone working on the GCS for you. This tool provides a more intuitive approach using two pots on your RC transmitter.

## How it works

One pot controls the output value that correlates to the 50% input (i.e. mid-stick position). The other pot will control the sensitivity of the collective from the 40% to the 60% input values (i.e. the gradient of the curve between 40% and 60%). It then converts the 50% value and the gradient to appropriate values for `IM_STAB_COL_2` and `IM_STAB_COL_3`. Once you are happy with the tune, flick the save switch on the transmitter and script will save the parameter values and exit the script.

The script updates the parameters every 0.5 seconds based on the position of the pots, allowing for easy tuning until the desired 'feel' is achieved.

It is worth noting that this script preserves the constraints set by ArduPilot:

0 <= `IM_STAB_COL_1` < `IM_STAB_COL_2` < `IM_STAB_COL_3` < `IM_STAB_COL_4` <= 100

As a result, if `IM_STAB_COL_1` or `IM_STAB_COL_4` are set to values that would violate the above constraint, after either `IM_STAB_COL_2` or `IM_STAB_COL_3` are changed by the script, then this script will modify the values of COL_1 and COL_4 to ensure this rule is met.

## Limits

The limits imposed on the values controlled by the pots are as follows:

- The mid-stick output value can be changed +/- 30%, centered on the initial mid-stick output value when the script is initialised.

- The maximum gradient is +100%

- The minimum gradient is +5%.

## Setup and Use

- If you have not done so already, follow the instructions on ArduPilot's wiki page to enable scripting.

- To get appropriate feedback from the script it is advised to set `SCR_DEBUG_LVL` to 3.

- Load Heli_IM_Col_Tune.lua to the 'scripts' folder on your flight controller.

- Set `RC<X>_OPTION` to 300 for the RC input channel that corresponds to the pot that you would like to control the mid-stick output value.

- Set `RC<X>_OPTION` to 301 for the RC input channel that corresponds to the pot that you would like to use to set the collective's sensitivity, around the mid-stick value.

- Set `RC<X>_OPTION` to 302 for the RC input channel that corresponds to the switch that you would like to use to save the parameters and exit the script.

- Note that the script will only register the assigned RC functions when first booting up the flight controller. Any changes to the RC allocations will require a reboot.

- Note that `RC<X>_TRIM` values are ignored.

- It is advisable to start with your `IM_STAB_COL_<X>` curve set to defaults to start (0/40/60/100 respectively). Similarly, it is advisable to start with the 50% input pot set to the half-way point and your gradient pot set to maximum. This way, you will start with your parameter values at their default values.

- Ensure your save switch is set to low.

- Reboot your flight controller.

- Fly in stabilize and tune to get your desired collective 'feel' by adjusting the two pots. If you plan to use higher automated modes than stabilize, it is sensible to get your heli hovering at mid-stick to ensure a smoother mode change into and out of 'auto-collective' modes (e.g. AltHold and Loiter). Once happy with your tune set the save switch to high. The script will save the parameters and exit the script. If you do not save the params they will not persist after a reboot.

- Once you have tuned your `IM_STAB_COL_2` and `IM_STAB_COL_3` values using the script, remove the script from your flight controller and reset the `RC<X>_OPTION` parameters.

- If you wish to make any adjustments to `IM_STAB_COL_1` and `IM_STAB_COL_4` you can now do so using the normal parameters.

## Output Messages

### "LUA: IM_COL tune complete"

The script has finished and will not run again without a reboot.

### "LUA: RC channels not set"

One or more RC channels are not set to the scripting channels (300,301, or 302). Set them and reboot flight controller.

### "LUA: IM_COL setter stopped"

There has been a fault and the script has exited. This is caused by the script being unable to read the `IM_STB_VOL_<X>` parameter values. Another message will precede this one, stating which parameter could not be retrieved.

### "LUA: params saved"

Parameters successfully saved.

### "LUA: param set failed"

Failed to set parameter. Script will persist to try and set parameters without exiting. If this message continues to show, consider landing and investigating the underlying issue.

0 comments on commit 32de8d7

Please sign in to comment.