mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_OpticalFlow: fixed default pixart flow scaling
This commit is contained in:
parent
9b93e12bbb
commit
52715c5d16
@ -49,7 +49,7 @@ private:
|
|||||||
static const uint8_t srom_data[];
|
static const uint8_t srom_data[];
|
||||||
static const uint8_t srom_id;
|
static const uint8_t srom_id;
|
||||||
static const RegData init_data[];
|
static const RegData init_data[];
|
||||||
const float flow_pixel_scaling = 1.0e-3;
|
const float flow_pixel_scaling = 1.26e-3;
|
||||||
|
|
||||||
// setup sensor
|
// setup sensor
|
||||||
bool setup_sensor(void);
|
bool setup_sensor(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user