mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: rename OpticalFlow class to AP_OpticalFlow
Brings us in-line with other classes in ArduPilot. Removes ambiguity with AP_HAL::OpticalFlow which can cause compilation errors as we start to make code more portable across targets
This commit is contained in:
parent
082eb83f30
commit
4139b7a548
@ -25,7 +25,6 @@
|
|||||||
#include <AP_Airspeed/AP_Airspeed.h>
|
#include <AP_Airspeed/AP_Airspeed.h>
|
||||||
#include <AP_InertialSensor/AP_InertialSensor.h>
|
#include <AP_InertialSensor/AP_InertialSensor.h>
|
||||||
|
|
||||||
class OpticalFlow;
|
|
||||||
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
#define AP_AHRS_TRIM_LIMIT 10.0f // maximum trim angle in degrees
|
||||||
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
||||||
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
||||||
|
Loading…
Reference in New Issue
Block a user