mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 10:38:28 -04:00
AP_OpticalFlow : Add parameter for flow rate scale factor correction
This commit is contained in:
parent
2500f7e9c2
commit
eec49ce1dd
@ -64,8 +64,9 @@ void AP_OpticalFlow_PX4::update(void)
|
||||
_device_id = report.sensor_id;
|
||||
_surface_quality = report.quality;
|
||||
if (report.integration_timespan > 0) {
|
||||
_flowRate.x = report.pixel_flow_x_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the X sensor axis
|
||||
_flowRate.y = report.pixel_flow_y_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the Y sensor axis
|
||||
float scaleFactor = 0.01f * float(100 + _scaler);
|
||||
_flowRate.x = scaleFactor * report.pixel_flow_x_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the X sensor axis
|
||||
_flowRate.y = scaleFactor * report.pixel_flow_y_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the Y sensor axis
|
||||
_bodyRate.x = report.gyro_x_rate_integral / (report.integration_timespan / 1e6f); // rad/sec measured inertially about the X sensor axis
|
||||
_bodyRate.y = report.gyro_y_rate_integral / (report.integration_timespan / 1e6f); // rad/sec measured inertially about the Y sensor axis
|
||||
} else {
|
||||
|
@ -10,6 +10,14 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] PROGMEM = {
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_ENABLE", 0, OpticalFlow, _enabled, 0),
|
||||
|
||||
// @Param: SCALER
|
||||
// @DisplayName: Optical flow scale factor
|
||||
// @Description: This sets the percentage scale factor correction applied to the flow sensor optical rates. It can be used to correct for variations in effective focal length.
|
||||
// @Range: -20 +20
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_SCALER", 1, OpticalFlow, _scaler, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -79,6 +79,7 @@ protected:
|
||||
|
||||
// parameters
|
||||
AP_Int8 _enabled; // enabled/disabled flag
|
||||
AP_Int8 _scaler; // flow angular rate correction percentage
|
||||
|
||||
// internal variables
|
||||
uint8_t _device_id; // device id
|
||||
|
Loading…
Reference in New Issue
Block a user