mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
OptFlow: remove unused variables
Saves 24bytes RAM by removing several static variables that were used only for internal calculations
This commit is contained in:
parent
b907263685
commit
d19b566d97
@ -43,19 +43,17 @@ void AP_OpticalFlow::update_position(float roll, float pitch, float sin_yaw, flo
|
||||
{
|
||||
float diff_roll = roll - _last_roll;
|
||||
float diff_pitch = pitch - _last_pitch;
|
||||
float change_x, change_y; // actual change in x, y coordinates
|
||||
|
||||
// only update position if surface quality is good and angle is not
|
||||
// over 45 degrees
|
||||
if( surface_quality >= 10 && fabsf(roll) <= FORTYFIVE_DEGREES
|
||||
&& fabsf(pitch) <= FORTYFIVE_DEGREES ) {
|
||||
altitude = max(altitude, 0);
|
||||
// calculate expected x,y diff due to roll and pitch change
|
||||
exp_change_x = diff_roll * radians_to_pixels;
|
||||
exp_change_y = -diff_pitch * radians_to_pixels;
|
||||
altitude = max(altitude, 0);
|
||||
|
||||
// real estimated raw change from mouse
|
||||
change_x = dx - exp_change_x;
|
||||
change_y = dy - exp_change_y;
|
||||
// change in position is actual change measured by sensor (i.e. dx, dy) minus expected change due to change in roll, pitch
|
||||
change_x = dx - (diff_roll * radians_to_pixels);
|
||||
change_y = dy - (-diff_pitch * radians_to_pixels);
|
||||
|
||||
float avg_altitude = (altitude + _last_altitude)*0.5f;
|
||||
|
||||
|
@ -57,17 +57,12 @@ public:
|
||||
void update_position(float roll, float pitch, float sin_yaw, float cos_yaw, float altitude);
|
||||
|
||||
// public variables
|
||||
int16_t raw_dx; // raw sensor change in x and y position (i.e. unrotated)
|
||||
int16_t raw_dy; // raw sensor change in x and y position (i.e. unrotated)
|
||||
uint8_t surface_quality; // image quality (below 15 you can't trust the dx,dy values returned)
|
||||
int16_t dx,dy; // rotated change in x and y position
|
||||
uint32_t last_update; // millis() time of last update
|
||||
float field_of_view; // field of view in Radians
|
||||
float scaler; // number returned from sensor when moved one pixel
|
||||
|
||||
// public variables for reporting purposes
|
||||
float exp_change_x, exp_change_y; // expected change in x, y coordinates
|
||||
float change_x, change_y; // actual change in x, y coordinates
|
||||
float x_cm, y_cm; // x,y position in cm
|
||||
|
||||
protected:
|
||||
|
@ -29,7 +29,6 @@ extern const AP_HAL::HAL& hal;
|
||||
AP_OpticalFlow_ADNS3080::AP_OpticalFlow_ADNS3080()
|
||||
{
|
||||
field_of_view = AP_OPTICALFLOW_ADNS3080_08_FOV;
|
||||
scaler = AP_OPTICALFLOW_ADNS3080_SCALER_1600;
|
||||
}
|
||||
|
||||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
@ -176,6 +175,7 @@ void AP_OpticalFlow_ADNS3080::write_register(uint8_t address, uint8_t value)
|
||||
void AP_OpticalFlow_ADNS3080::update(void)
|
||||
{
|
||||
uint8_t motion_reg;
|
||||
int16_t raw_dx, raw_dy; // raw sensor change in x and y position (i.e. unrotated)
|
||||
surface_quality = read_register(ADNS3080_SQUAL);
|
||||
hal.scheduler->delay_microseconds(50);
|
||||
|
||||
@ -267,9 +267,9 @@ void AP_OpticalFlow_ADNS3080::update_conversion_factors()
|
||||
{
|
||||
// multiply this number by altitude and pixel change to get horizontal
|
||||
// move (in same units as altitude)
|
||||
conv_factor = ((1.0f / (float)(ADNS3080_PIXELS_X * scaler))
|
||||
conv_factor = ((1.0f / (float)(ADNS3080_PIXELS_X * AP_OPTICALFLOW_ADNS3080_SCALER_1600))
|
||||
* 2.0f * tanf(field_of_view / 2.0f));
|
||||
// 0.00615
|
||||
radians_to_pixels = (ADNS3080_PIXELS_X * scaler) / field_of_view;
|
||||
radians_to_pixels = (ADNS3080_PIXELS_X * AP_OPTICALFLOW_ADNS3080_SCALER_1600) / field_of_view;
|
||||
// 162.99
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user