mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow : Remove gyro scale factor user adjustable parameter
No longer required because bug in flow sensor has been fixed.
This commit is contained in:
parent
898ad7432b
commit
7ec8dfebcf
|
@ -65,11 +65,10 @@ void AP_OpticalFlow_PX4::update(void)
|
|||
_surface_quality = report.quality;
|
||||
if (report.integration_timespan > 0) {
|
||||
float flowScaleFactor = 0.01f * float(100 + _flowScaler);
|
||||
float gyroScaleFactor = 0.01f * float(100 + _gyroScaler);
|
||||
_flowRate.x = flowScaleFactor * report.pixel_flow_x_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the X sensor axis
|
||||
_flowRate.y = flowScaleFactor * report.pixel_flow_y_integral / (report.integration_timespan / 1e6f); // rad/sec measured optically about the Y sensor axis
|
||||
_bodyRate.x = gyroScaleFactor * report.gyro_x_rate_integral / (report.integration_timespan / 1e6f); // rad/sec measured inertially about the X sensor axis
|
||||
_bodyRate.y = gyroScaleFactor * report.gyro_y_rate_integral / (report.integration_timespan / 1e6f); // rad/sec measured inertially 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 {
|
||||
_flowRate.x = 0.0f;
|
||||
_flowRate.y = 0.0f;
|
||||
|
|
|
@ -18,14 +18,6 @@ const AP_Param::GroupInfo OpticalFlow::var_info[] PROGMEM = {
|
|||
// @User: Standard
|
||||
AP_GROUPINFO("_FSCALER", 1, OpticalFlow, _flowScaler, 0),
|
||||
|
||||
// @Param: GSCALER
|
||||
// @DisplayName: Gyro scale factor correction
|
||||
// @Description: This sets the percentage scale factor correction applied to the flow sensor gyro rates. It can be used to correct for sensor errors.
|
||||
// @Range: -20 +20
|
||||
// @Increment: 1
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("_GSCALER", 2, OpticalFlow, _gyroScaler, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -80,7 +80,6 @@ protected:
|
|||
// parameters
|
||||
AP_Int8 _enabled; // enabled/disabled flag
|
||||
AP_Int8 _flowScaler; // flow angular rate correction percentage
|
||||
AP_Int8 _gyroScaler; // gyro angular rate correction percentage
|
||||
|
||||
// internal variables
|
||||
uint8_t _device_id; // device id
|
||||
|
|
Loading…
Reference in New Issue