Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Scripting/AP_RangeFinder: Add lua scripting based RangeFinder #20015

Open
wants to merge 9 commits into
base: master
Choose a base branch
from

Conversation

rishabsingh3003
Copy link
Contributor

Thanks to @IamPete1 for teaching me how to add bindings for the slightly complicated backend methods!

This PR attempts to add the ability for a user to add a custom Lua script-based rangefinder backend.
An example script has been attached where this is useful:
All sensors attached in the same direction are checked against each other. If any of the sensors report a disparity greater than a particular margin, we ignore all the readings. Therefore, we can now also add such custom behaviour with this PR (instead of just using it to add new drivers for new sensors).

libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp Outdated Show resolved Hide resolved
libraries/AP_RangeFinder/AP_RangeFinder.cpp Outdated Show resolved Hide resolved
libraries/AP_Scripting/generator/description/bindings.desc Outdated Show resolved Hide resolved
AP_RangeFinder_Backend *backend = get_backend(i);
if (backend != nullptr &&
backend->orientation() == orientation &&
backend->primary_sensor()) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We could also change to a "use" method. Like airspeed and compass. Rather than overriding with the scripting backend you would instead set to not use.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes I think that adds moe functionality too. Done that

@muramura
Copy link
Contributor

I want to add a range finder for my TMF8821 with a LUA script.
What is the problem with this LUA driver?

TMF8821:.
https://www.sparkfun.com/products/19451

// Set the distance based on a Lua Script
bool AP_RangeFinder_Lua::handle_script_msg(float dist_m)
{
// only accept distances for the configured orentation
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Comment is wrong.

{
//Time out on incoming data; if we don't get new
//data in 500ms, dump it
if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I quite like this sort of timeout, however we did not implement one for EFI, there the script sets last reading itself. That does mean the script can report that rangefinder is lost, eg it can still set the distance without updating the timeout. Here we cant tell the difference between the script stopping and the script loosing connection with the sensor. However it does require that the script fill that last time in correctly.

#if AP_SCRIPTING_ENABLED
_add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance);
break;
#endif
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

break after endif

for (uint8_t i=0; i<num_instances; i++) {
AP_RangeFinder_Backend *backend = get_backend(i);
if (backend != nullptr &&
backend->orientation() == orientation &&
backend->status() == Status::Good) {
backend->status() == Status::Good &&
backend->use_sensor()) {
return backend;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

need to check all uses of get_backend() to ensure they obey use setting
eg: NavEKF3_core::readRangeFinder()
also AP_Proximity_RangeFinder::update

return update, update_rate_ms -- check again in 25ms
end

return update(), 5000 -- first data may be checked 5 seconds after start-up
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add protected_wrapper()

@tridge tridge removed the DevCallEU label Nov 2, 2022
@@ -39,7 +39,7 @@ void NavEKF3_core::readRangeFinder(void)
if (sensor == nullptr) {
continue;
}
if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == AP_DAL_RangeFinder::Status::Good)) {
if ((sensor->orientation() == ROTATION_PITCH_270) && (sensor->status() == AP_DAL_RangeFinder::Status::Good) && sensor->use_sensor()) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this really is a mess, a function that does this would make it a lot cleaner:

  • get_backend_orient_use(ROTATION_PITCH_270);
    that would return the first in-range rangefinder with the given orient that has USE=1

---@return number
function AP_RangeFinder_Backend_ud:distance() end

-- Returns true if backend has new data
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

don't need has_data(), use status()

@@ -191,6 +199,8 @@ singleton RangeFinder method status_orient uint8_t Rotation'enum ROTATION_NONE R
singleton RangeFinder method has_data_orient boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1
singleton RangeFinder method get_pos_offset_orient Vector3f Rotation'enum ROTATION_NONE ROTATION_MAX-1

singleton RangeFinder method get_backend AP_RangeFinder_Backend uint8_t 0 RANGEFINDER_MAX_INSTANCES-1
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

should be skip_check, and change the other rangefinder ones to skip_check, and use nil check in script

@tridge
Copy link
Contributor

tridge commented Mar 25, 2023

@rishabsingh3003 any progress?

@rishabsingh3003
Copy link
Contributor Author

@tridge #22933 Already got merged with the Scripting rangefinder backend. What hasn't gotten in is the Rangefinder enable parameter, which will allow us to do selectively turn off rangefinder backends. The reason is that I feel several EKF changes should be made (more than the one already present in this PR) because the rangefinder parts have lots of assumptions and bugs. I can probably push a PR tomorrow if you'd like but I would benefit from a 5 min discussion before on the things that require changing.

@lvale
Copy link
Member

lvale commented Aug 1, 2023

@rishabsingh3003 Hi again. Is this on hold or do you plan to finish it, after Tridge's requested changes ?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

6 participants