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

AP_RangeFinder: Benewake sends max-range+1m when out of range #9727

Merged
merged 3 commits into from Nov 10, 2018

Conversation

rmackay9
Copy link
Contributor

@rmackay9 rmackay9 commented Nov 8, 2018

This PR corrects two issues discovered during Copter-3.6.1-rc1 testing (see discussion here):

  • The Benewake lidar driver returns the RNGFND_MAX_CM + 1m if the lidar goes out of range. Previously it would ignore these readings but this would lead to the lidar's state becoming "NoData" when really it's "OutOfRangeHigh". The 1m addition to the defined maximum range is a bit arbitrary but I wanted to ensure that it's significantly beyond the maximum so that no rounding errors could lead to it being considered within range. Below is a screen shot of a test where the RNGFND_MAX_CM was set to 1500 so the lidar reports 16m when out-of-range.

benewake-test

  • Copter's extended system status message to the GCS reports the lidar as healthy as long as it's returning data. Previously the lidar was only reported healthy if the lidar range was within the MIN and MAX. In my view, "healthy" means the lidar is operating as expected and no action is required from the user. It's a normal and expected thing in most situations that the lidar will go out of range of the ground so I don't think it's good to report the lidar as "unhealthy" in these situations.

OXINARF
OXINARF previously requested changes Nov 8, 2018
Copy link
Member

@OXINARF OXINARF left a comment

Choose a reason for hiding this comment

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

Second part is OK.

First part I would prefer to see it use the signal_ok, after all, that's precisely why it was there. It seems it was misused in the update method; in my opinion we only to change:

  • get_reading to initialize signal_ok to false
  • update to:
    bool signal_ok = false;
    if (get_reading(state.distance_cm, signal_ok)) {
      state.last_reading_ms = AP_HAL::millis();
      update_status();
    } else if (signal_ok) {
      set_status(RangeFinder::RangeFinder_OutOfRangeHigh);
    } else if (AP_HAL::millis() - state.last_reading_ms > 200) {
      set_status(RangeFinder::RangeFinder_NoData);
    }
    

@rmackay9
Copy link
Contributor Author

rmackay9 commented Nov 8, 2018

@OXINARF, thanks very much for the review!

@rmackay9
Copy link
Contributor Author

rmackay9 commented Nov 8, 2018

@OXINARF, thinking about this a bit more.. the proposed code won't quite work because last_reading_ms won't be updated so the sensor's health will go bad. I.e. it's status will soon be set to NoData..

So I'm still thinking about how to handle this..

@rmackay9
Copy link
Contributor Author

rmackay9 commented Nov 8, 2018

@OXINARF, how do you feel about this change? Instead of making more use of "signal_ok" I've removed it and in cases where we were using it, we now just set the distance to out-of-range. I also made a couple of other minor simplifications.

Here's a graph of the RFND.Dist1 during a test after making this change.
test4-output

@OXINARF
Copy link
Member

OXINARF commented Nov 8, 2018

@rmackay9 How does it set the out-of-range status? It looks like the value would be used as valid, unless the user explicitly sets the max range which triggers the out-of-range status; we rely on that on some drivers, but I think that in drivers where we know it is out-of-range we shouldn't require it.

@rmackay9
Copy link
Contributor Author

rmackay9 commented Nov 9, 2018

@OXINARF, once the update_status() call is made it will check that the new distance reading vs the "max_distance_cm" (aka RNGFND_MAX_CM) and because the distance was set to "max_distance_cm + 1m" it will set the status to OutOfRangeHigh.

The max distance is defaulted to 700cm and it always needs to be defined. It's not one of those parameters where setting it to zero removes the limit.

@OXINARF
Copy link
Member

OXINARF commented Nov 9, 2018

Ok, makes sense. Can we add the following in the constructor?

state.max_distance_cm.set_default(BENEWAKE_DIST_MAX_CM);

This way if the user doesn't set it, we set the default to a more sane value.

By the way, squashing third commit with first might be a good idea.

peterbarker and others added 3 commits November 10, 2018 10:58
…able

This means the sensor is healthy even if it is out of range.

This is a partial revert of commit ArduPilot@724f34c#diff-577a72d2550199fabbdfd77fa5890368R408
this should be a non-functional change
@rmackay9
Copy link
Contributor Author

Thanks I've squashed and created an issue to better default the max range for all lidar.

I'll merge this when travis and semaphore say it's OK.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Copter 3.6 Backports
  
3.6.2-rc1
Development

Successfully merging this pull request may close these issues.

None yet

3 participants