Added VSPF_MODE

This commit is contained in:
George Zogopoulos 2024-12-12 13:17:27 +01:00
parent ab195c8045
commit adf6a2c9c8
2 changed files with 107 additions and 37 deletions

View File

@ -1,24 +1,17 @@
-- VSPeak_flow_meter.lua: Driver for the VSPeak Modell fuel flow sensor.
--
-- Setup
-- 1. Place this script in the "scripts" directory of the autopilot.
-- 2. Connect the sensor to a serial port (for now referred to as SERIAL*)
-- 3. Enable the scripting engine via SCR_ENABLE.
-- 4. Set SERIAL*_BAUD = 19 (19200)
-- 5. Set SERIAL*_PROTOCOL = 28 (Scripting)
-- 6. Set BATT*_MONITOR = 29 (Scripting)
-- 7. Set BATT*_CAPACITY to the amount of ml your tank is filled with.
-- Read the accompanying .md file.
--
-- Usage
-- No further action required.
-- Read the accompanying .md file.
--[[
Global definitions
--]]
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
local SCRIPT_NAME = "VSPeak Modell flow meter driver"
local NUM_SCRIPT_PARAMS = 3
local NUM_SCRIPT_PARAMS = 4
local LOOP_RATE_HZ = 10
local last_warning_time_ms = uint32_t(0)
local WARNING_DEADTIME_MS = 1000
@ -84,9 +77,13 @@ local VSPF_BAT_IDX = bind_add_param('BAT_IDX', 2, 2)
local VSPF_CFACT = bind_add_param('CFACT', 3, 1)
--[[
Potential additions:
- The scripting switch.
// @Param: MODE
// @DisplayName: Sensor operating mode
// @Description: 0: The sensor will save the fuel consumption across power resets. 1: The sensor will reset the power consumption.
// @User: Standard
--]]
local VSPF_MODE = bind_add_param('MODE', 4, 0)
-- Warn the user, throttling the message rate.
function warn_user(msg, severity)
severity = severity or MAV_SEVERITY.WARNING -- Optional severity argument.
@ -180,6 +177,10 @@ function update_battery()
bat_state:current_amps(state.flow/1000*60.0*VSPF_CFACT:get()) -- Convert from ml/min to l/h.
bat_state:temperature(0)
if VSPF_MODE:get() == 1 then
bat_state:consumed_mah(state.fuel_ml*VSPF_CFACT:get())
end
battery:handle_scripting(VSPF_BAT_IDX:get()-1, bat_state)
end

View File

@ -4,21 +4,47 @@ This driver implements support for the VSPeak Modell flow meter sensor.
https://www.vspeak-modell.de/en/flow-meter
# Parameters
The script used the following parameters:
## VSPF_ENABLE
Setting this to 1 enables the driver.
# Setup
First of all, calibrate and configure the flow meter according to the
manufacturer instructions. Set your configuration with the `FLOW.txt` file,
placed in the SD card in the sensor itself.
For this script, the consumed/level FUEL display setting is not relevant,
as only the current flow is used.
## Mode selection
There are two ways to operate this sensor.
**A: Save consumed volume**
Under this mode, the sensor will remember how much fuel volume was consumed
across power cycles. This allows you to have an accurate fuel tank level
reading even if you power down or reboot the autopilot.
However, you will have to manually reset the sensor each time you refuel the
vehicle. This is achieved by issuing a PWM signal to the sensor.
To set that mode, you need to set the `Auto Reset` setting to `Power ON` in
the `FLOW.txt` sensor settings file.
For more information, read the sensor manual.
**B: Forget consumed volume**
Under this mode, the consumed fuel volume will reset after each power cycle.
This is especially important for fuel-powered vehicles, as there is no
equivalent of a voltage reading to initialize the remaining energy percentage.
On the upside, you do not need to wire a PWM signal to the sensor to reset the
consumed volume measurement. You will have to update the starting volume
manually.
To set that mode, you need to set the `Auto Reset` setting to `Power OFF` in
the `FLOW.txt` sensor settings file.
For more information, read the sensor manual.
## Sensor configuration
Calibrate the flow meter according to the manufacturer instructions.
Additionally, configure the sensor to report the consumed fuel volume, by
setting the `FUEL display` to `consumed` in `FLOW.txt`.
## Script parameter settings
Once this is done, perform the following steps.
@ -31,10 +57,21 @@ Once this is done, perform the following steps.
Then, decide which battery monitor will be assigned to the sensor (for now
referred to as `BATT*`).
6. Set `BATT*_MONITOR` = 29 (Scripting)
7. Set `BATT*_CAPACITY` to the amount of ml your tank is filled with. This can
vary from flight to flight.
If operating under Mode A (Save consumed), you do not need to update this
value with what is remaining in the tank after every reboot.
If you are operating under Mode B (Reset consumed), you will have to update
this value after every reboot, if fuel was consumed in the meantime.
8. Tell the script which battery monitor is employed via `VSPF_BAT_IDX`.
9. Enable the script itself with `VSPF_ENABLE=1`.
9. Set the selected operation mode:
For mode A (save consumed), set `VSPF_MODE=0`.
For mode B (reset consumed), set `VSPF_MODE=1`.
10. Enable the script itself with `VSPF_ENABLE=1`.
# Operation
@ -45,3 +82,35 @@ will display in the corresponding `BATTERY_STATUS` MAVLink message:
You can use the parameter `VSPF_CFACT` to compensate for scaling errors in the
sensor setup. 1 is the default value. Set to <1 if the measurements are too high.
## Refueling
When refueling, make sure to set `BATT*CAPACITY` to the actual, new value of
the fuel volume that is in the tank.
If operating under mode A (Save consumed), reset the sensor by triggering the
PWM pulse.
# Parameters
The script used the following parameters:
## VSPF_ENABLE
Setting this to 1 enables the driver.
## VSPF_BAT_IDX
Selects which battery monitor instance will be fed the fuel consumption
information. 1-indexed.
## VSPF_CFACT
This is multiplicative factor to correct the measured flow. Set to <1 if your
sensor measures too high and vice versa.
## VSPF_MODE
Tells the script which mode it is operating in.
0: Mode A, save consumption.
1: Mode B, reset consumption.