Send sensor distance by using serial in Script

I have firmware version 4.5.0. I am going to use the following functions to get the distance from the sensor and send it to the flight control by serial.

-- find serial Defined As 
local port = serial:find_serial(0)

--find Terrain Sensor Backend
local terrainSensor = rangefinder:get_backend(0)

local define_distance = 400

-- connect to the Serial port
port:begin(57600)
port:set_flow_control(0)

function rangefinder_data()
    if port:available() > 0 then
        
        if terrainSensor ~= nil then
            terrainSensor:handle_script_msg(define_distance / 100)
            gcs:send_text(6,"distance set on rangefinder.")
        end
        
    end
    return rangefinder_data , 4000
end

return rangefinder_data , 1000

The parameters I set:
SERIAL2_PTOROCOL = 28
RNGFND1_TYPE = 36
RNGFND1_ORIENT = 25

My script runs correctly in version 4.5.0, but in version 4.6.0, the sensor distance is not sent to flight control.
output Script in Version 4.5.0:
rangefinder in V4.5.0

output Script in Version 4.6.0:
rangefinder in V4.6.0
debug massage V4.6.0
and We can see the debug text, this means there is no problem in the execution.

Can you help me how to get the sensor distance with serial and send it to the flight control in the new version?

ardupilot
lua-script
ArduPilot Lua Scripting

you are using the modified Firmware , please test your script with legacy version and install latest firmware release from Mission Planner on your bord and repost the result .

I installed version 4.5.1 which was the last stable version of Ardupilot with Mission Planner software. The result I got was as follows:
rangefinder in V4.5.1
debug massage V4.5.1

Also, I downloaded and installed version 4.6.0 from the Ardupilot site, but the result was like this:
rangefinder in V4.6.0
debug massage V4.6.0

ok , please upload your Full parameter File for double check .

this is my parameter file to send sensor distance by serial:
parameter file.param (26.1 KB)

I checked and found that Ardupilot version copter-4.4.4 shows the sensor distance.
rangefinder in V4.4.4
debug massage V4.4.4

Then I checked the changes of AP_Rangefinder_lua version copter-4.4.4 with version copter-4.5.1 and the result is as follows:

As always, there is an example to guide you:

I checked this by myself and this bug is true .
this function is changed in recently release in AP_RangeFinder_Lua.cpp

// Process range finder data from a lua driver - legacy interface. This method takes
// a distance measurement and fills in the pending state structure. In this legacy mode
// the lua script only passes in a distance measurement and does not manage the rest
// of the fields in the state structure.
bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) {

    const uint32_t now = AP_HAL::millis();

    WITH_SEMAPHORE(_sem);

    // Time out on incoming data; if we don't get new data in 500ms, dump it
    if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) {
        set_status(_state_pending, RangeFinder::Status::NoData);
    } else {
        _state_pending.last_reading_ms = now;
        _state_pending.distance_m = dist_m;
        _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN;
        _state_pending.voltage_mv = 0;
        update_status(_state_pending);
    }

    return true;
}

As you can see in the following Function

_state_pending.last_reading_ms never update if

 // Time out on incoming data; if we don't get new data in 500ms, dump it
    if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) {
        set_status(_state_pending, RangeFinder::Status::NoData);
      }

happend

so Data will never Apply on _state_pending

in other hand why we have to check time out on handle_script_msg ?!
this function called when valid data is sent from script and backend must put the data on line not check the time out !!

I will modified this and reply the result

// Process range finder data from a lua driver - legacy interface. This method takes
// a distance measurement and fills in the pending state structure. In this legacy mode
// the lua script only passes in a distance measurement and does not manage the rest
// of the fields in the state structure.
bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) {

    const uint32_t now = AP_HAL::millis();

    WITH_SEMAPHORE(_sem);
    _state_pending.last_reading_ms = now;
    _state_pending.distance_m = dist_m;
    _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN;
    _state_pending.voltage_mv = 0;
    update_status(_state_pending);

    return true;
}
1 Like

@nrgs_barani, @AhmadAli_Malakooti,

Thanks very much for the report and investigation. I’ve added this to the 4.5 issues list.

@AhmadAli_Malakooti,

Are you happy to raise a PR to fix this? No pressure of course.

1 Like

It is true that after editing the firmware, this problem will be solved and the distance of the sensor will be correctly sent to the Flight Control.
range finder distance after debug

Thank you for your help.

1 Like

OK . I Cloned and modified the Source by my self but I haven’t raise a PR to Main Git before . I have to learn the correct procedure first to prevent the false PR . If you have helpful link or document Please share it with me . thank you

1 Like

Hi @AhmadAli_Malakooti,

We’ve got a wiki page here which describes somewhat how to raise a PR to change PA’s “master” branch.

https://ardupilot.org/dev/docs/submitting-patches-back-to-master.html

FYI @rishabsingh3003

Hmmm… reading the code before & after the change, it seems that the design intent is that measurement frequency should be > 2Hz. However, there was a bug in the code where the timeout was ignored. The change in AP_RangeFinder: Add LUA interface to access Range Finder state · ArduPilot/ardupilot@2cc63f5 · GitHub fixed the bug.

You could fix your script to send readings more often, say 4Hz.

Or a PR could change the timeout to something like 5000ms, though that might cause other problems.

Note that the MAVLink timeout is 500ms as well.

Edit: oops, I was wrong, this is a bug. The timeout check should be on the update call, not the handle_msg call. Proposed fix: AP_RangeFinder: fix Lua timeout by clydemcqueen · Pull Request #26829 · ArduPilot/ardupilot · GitHub

1 Like

Hi!
Thank you so much for the fix. It is indeed a bug. I just need to test your PR once on real hardware and then I’ll help get it merged.
@nrgs_barani in the mean time you could use the new “structure” method in handle_script_msg(), in your lua script. That should still work. Its the “legacy” method that is broken as far as I can tell (which is what you are using in your script). The next beta release should fix it all. Thanks for the report!

3 Likes