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

VL53L1X Region of Interest & Distance Mode Setting #16695

Closed
wants to merge 69 commits into from

Conversation

dirksavage88
Copy link
Contributor

Describe problem solved by this pull request
Distance sensor driver for the VL53L1X has region of interest (ROI) that can be programmed, but the set of functions were not implemented in the VL53L1X ul driver integrated into PX4. The ROI settings allow better resolution when changing the ranging area within the field of view. Distance is decreased but resolution is increased allowing the sensor to pick up smaller objects at sub-1 meter ranges.

Describe your solution
Utilized the ST vl53l1x ultra lite driver manual to implement two functions that allow a programmable region of interest, also created a distance mode class data member that allows easier setting, this defaults to a short distance mode for better resolution. These two settings lay the ground work for using multiple simultaneous zone detection with multiple distance sensors (2d lidar)

Describe possible alternatives
Utilize code from a larger driver that allows Lidar sensing with multiple sensors. However, this has larger code footprint.

Test data / coverage
Tested on bench setting with real hardware ITL. Plot from flight review:
bokeh_plot
attached

@dirksavage88 dirksavage88 changed the base branch from master to beta January 30, 2021 00:32
@dirksavage88 dirksavage88 changed the base branch from beta to master January 30, 2021 00:34
@dagar
Copy link
Member

dagar commented Jan 30, 2021

Interesting, I was considering directly carrying the (big ugly) ST driver to make more of these features accessible.

@@ -765,6 +765,17 @@ MavlinkReceiver::handle_message_distance_sensor(mavlink_message_t *msg)
// quality value. Also it comes normalised between 1 and 100 while the uORB
// signal quality is normalised between 0 and 100.
ds.signal_quality = dist_sensor.signal_quality == 0 ? -1 : 100 * (dist_sensor.signal_quality - 1) / 99;
qt = const_cast<float*>(ds.q);
//mavlink clients
mavlink_msg_distance_sensor_send(MAVLINK_COMM_0, ds.timestamp, ds.min_distance, ds.max_distance, ds.current_distance, ds.type, ds.device_id, ds.orientation, ds.variance, ds.h_fov, ds.v_fov, qt, ds.signal_quality);
Copy link
Member

Choose a reason for hiding this comment

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

Crossing mavlink channels (owned by separate mavlink instances) doesn't look quite right, could you explain what you're trying to accomplish here?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I'll be honest, I was troubleshooting mavlink messages issues. Turns out the sensor itself didn't like 5 volts and would refuse to work when connected to a LiPO, but would work perfectly fine in USB. Thought it was a telemetry vs usb issue. Can remove, unnecessary.

Copy link
Member

Choose a reason for hiding this comment

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

Please remove yes.

@@ -222,35 +232,55 @@ void VL53L1X::RunImpl()
{
uint8_t dataReady = 0;

uint8_t roiCenter[] = {247, 215, 183, 167, 151};
Copy link
Member

Choose a reason for hiding this comment

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

Comment explain these magic numbers?

Is it desirable to configure a specific ROI for different usage?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

logic to these numbers can be found in vl53l1x multiple detection zone pdf.

Copy link
Member

Choose a reason for hiding this comment

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

Please use defines to encode them.


if ((ret != PX4_OK) | (rangeStatus != PX4_OK)) {
if ((ret != PX4_OK) | (rangeStatus == 13)) {
Copy link
Member

Choose a reason for hiding this comment

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

Is there a range status define you can use instead of the magic number (13)?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

this is a range status that indicates ROI is 'out of bounds', also referenced in the ST multiple zone manaul

Copy link
Member

Choose a reason for hiding this comment

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

Please create const values for each of those, e.g. RANGE_STATUS_OUT_OF_BOUNDS for this one and then use it.

_px4_rangefinder.set_max_distance(2.f);
_px4_rangefinder.set_fov(math::radians(25.f));

if (distance_mode == 1) {
Copy link
Member

Choose a reason for hiding this comment

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

Please use defines instead of magic numbers.

@@ -166,16 +176,16 @@ VL53L1X::~VL53L1X()
int VL53L1X::collect()
{
uint8_t ret = 0;
uint8_t rangeStatus;
uint8_t rangeStatus = 0;
Copy link
Member

Choose a reason for hiding this comment

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

Needs a define here as well.

@@ -191,7 +201,7 @@ int VL53L1X::collect()
}

perf_end(_sample_perf);

Copy link
Member

Choose a reason for hiding this comment

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

Please remove this whitespace change (run make format)

@@ -123,13 +123,16 @@ class VL53L1X : public device::I2C, public I2CSPIDriver<VL53L1X>
void stop();

virtual int init() override;

Copy link
Member

Choose a reason for hiding this comment

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

Unnecessary whitespace change.

@@ -22,7 +22,7 @@ px4_add_board(
camera_trigger
differential_pressure # all available differential pressure drivers
distance_sensor # all available distance sensor drivers
distance_sensor/srf05 # Specific driver
distance_sensor/srf05 # Specific driver
Copy link
Member

Choose a reason for hiding this comment

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

Unnecessary whitespace change

{
// VL53L1X typical range 0-2 meters with 25 degree field of view
{
//Set distance mode (1 for ~2m ranging, 2 for ~4m ranging
Copy link
Member

Choose a reason for hiding this comment

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

Please use one space after // for every comment

VL53L1X_CheckForDataReady(&dataReady);

if (dataReady == 1) {
collect();
collect();
Copy link
Member

Choose a reason for hiding this comment

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

Whitespace / indentation change that should be removed (wrong indentation and it adds noise to the diff)

@mrpollo
Copy link
Contributor

mrpollo commented Feb 1, 2021

@dirksavage88 thanks for putting in the work to push this upstream, we would love to get this in soon, can you please check the CI errors and comments from the reviewers above? once you are ready for a new review please ping me

@dirksavage88
Copy link
Contributor Author

@dirksavage88 thanks for putting in the work to push this upstream, we would love to get this in soon, can you please check the CI errors and comments from the reviewers above? once you are ready for a new review please ping me

Hello @mrpollo ,

I have incorporated the changes in the latest commit, to include format changes. I have successfully built for my specific hardware target but not tested (SITL, HITL, etc).

@mrpollo
Copy link
Contributor

mrpollo commented Feb 1, 2021

Thanks @dirksavage88

Looks like the CI timeout is non-related to your changeset, I will ask for a final review from the team before merging.

@dirksavage88
Copy link
Contributor Author

@mrpollo Wasn't sure if the CI failures are related, but the SITL tests /build (tailsitter) and MAVROS mission tests / build rover, are those fails that can be remedied?

@mrpollo
Copy link
Contributor

mrpollo commented Feb 15, 2021

@dirksavage88 I don't think either of those failed tests has anything to do with your PR, I think we should proceed with a merge as soon as a reviewer with commit access has time to get this in.

Note: I restarted the continuous-integration/jenkins/pr-head action and is now passing 💚

I'm tracking the CI failures here in case anyone is interested in following up #16859 and #16745

@igalloway
Copy link
Contributor

Igor-Misic and others added 25 commits August 2, 2021 18:41
…on a bus

This also simplifies the API a bit, since we anyway have to change the
drivers to pass additional information (the bus device index).

The orientation flag is merged with the rotation.
Some targets don't build it (e.g. ark can bootloader)
… interest center setting and size

Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
…enge 2, Team SavageCabbage

Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
…agic #'s with global constants

Signed-off-by: Andrew Brahim <dirksavage88@gmail.com>
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
Signed-off-by: dirksavage88 <dirksavage88@gmail.com>
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.