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

Optical flow: compute velocity from corrected flow data for logging #16050

Merged
merged 4 commits into from
Oct 26, 2020

Conversation

bresch
Copy link
Member

@bresch bresch commented Oct 26, 2020

This is really useful to align the flow with the IMU data and verify that the compensation is properly done

update to PX4/PX4-ECL#920

includes:

  • logging of compensated optical flow data converted to velocity measurement in body and local frames
  • logging of un/compensated optical flow data for rate motion and synchronized gyro data
  • adjust scaling value of pmw3901 data (was off by 30%)
  • adjust delay parameter for pmw3901 for perfect synchronization with gyro data

Bench tested with pmw3901 optical flow sensor and Lanbao PSK-CM8JL65 range finder:
Note that I recently renamed the fields in optical_flow_vel so the signals in the screenshot below don't have the correct names
flow_scaled_to_gyro

@@ -324,8 +324,8 @@ PMW3901::RunImpl()
return;
}

delta_x = (float)_flow_sum_x / 500.0f; // proportional factor + convert from pixels to radians
delta_y = (float)_flow_sum_y / 500.0f; // proportional factor + convert from pixels to radians
delta_x = (float)_flow_sum_x / 385.0f; // proportional factor + convert from pixels to radians
Copy link
Member

Choose a reason for hiding this comment

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

Likely applies to the paw3902 as well.

Copy link
Member Author

Choose a reason for hiding this comment

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

@dagar I thought the same but don't have one to verify that; Are you sure that the scaling is the same?

Copy link
Member

Choose a reason for hiding this comment

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

Are you sure that the scaling is the same?

No, but it's currently the same hard coded magic number and "works". We could leave it alone for now and review optical_flow_vel when someone is able to do a test.

@@ -163,6 +163,7 @@ set(msg_files
wheel_encoders.msg
wind_estimate.msg
yaw_estimator_status.msg
optical_flow_vel.msg
Copy link
Member

Choose a reason for hiding this comment

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

Maybe prefix this message with estimator_ so we know where it's coming from?

optical_flow_vel_s flow_vel{};
flow_vel.timestamp_sample = timestamp;

_ekf.getFlowVelBody().copyTo(flow_vel.vel_body);
Copy link
Member

Choose a reason for hiding this comment

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

Could this be similar to vehicle_visual_odometry_aligned where it only publishes in the same cycle that new data was received, but after the EKF update?

Copy link
Member Author

@bresch bresch Oct 26, 2020

Choose a reason for hiding this comment

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

Not sure if it's worth doing this because the optical flow update rate is probably faster than the EKF update rate, but at least we don't publish it when there is no optical flow sensor

Copy link
Member

Choose a reason for hiding this comment

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

It's more of a log visibility (and minor optimization) thing, only having estimator_optical_flow_vel when you actually had optical_flow and were using it.

Getting the optical_flow data rate within the EKF update rate is one of the other reasons I was going to pipe it through the sensors module first.

@bresch bresch requested a review from dagar October 26, 2020 15:56
@bresch
Copy link
Member Author

bresch commented Oct 26, 2020

@dagar I addressed your comments, any other remarks?

@dagar
Copy link
Member

dagar commented Oct 26, 2020

@dagar I addressed your comments, any other remarks?

Thanks, good to go from my perspective.

dagar
dagar previously approved these changes Oct 26, 2020
@bresch
Copy link
Member Author

bresch commented Oct 26, 2020

unrelated SITL failure

This is important to align the flow with the IMU data and verify that
the compensation is properly done
This is the correct value for the most common optical flow sensor
@bresch
Copy link
Member Author

bresch commented Oct 26, 2020

@dagar I just squashed two commits together to make the history cleaner, could you approve again please?

dagar
dagar previously approved these changes Oct 26, 2020
@dagar dagar merged commit d5245a2 into master Oct 26, 2020
@dagar dagar deleted the pr-flow-vel-upstream branch October 26, 2020 18:10
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.

2 participants