mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: move DCM parameters into DCM header
This commit is contained in:
parent
74709c6292
commit
645a5302d0
@ -430,23 +430,6 @@ protected:
|
||||
// multi-thread access support
|
||||
HAL_Semaphore _rsem;
|
||||
|
||||
// settable parameters
|
||||
// these are public for ArduCopter
|
||||
AP_Float _kp_yaw;
|
||||
AP_Float _kp;
|
||||
AP_Float gps_gain;
|
||||
|
||||
AP_Float beta;
|
||||
|
||||
enum class GPSUse : uint8_t {
|
||||
Disable = 0,
|
||||
Enable = 1,
|
||||
EnableWithHeight = 2,
|
||||
};
|
||||
|
||||
AP_Enum<GPSUse> _gps_use;
|
||||
AP_Int8 _gps_minsats;
|
||||
|
||||
Matrix3f _custom_rotation;
|
||||
|
||||
// calculate sin/cos of roll/pitch/yaw from rotation
|
||||
|
@ -126,6 +126,24 @@ public:
|
||||
bool get_relative_position_NE_origin(Vector2f &posNE) const override;
|
||||
bool get_relative_position_D_origin(float &posD) const override;
|
||||
|
||||
protected:
|
||||
|
||||
// settable parameters
|
||||
AP_Float _kp_yaw;
|
||||
AP_Float _kp;
|
||||
AP_Float gps_gain;
|
||||
|
||||
AP_Float beta;
|
||||
|
||||
enum class GPSUse : uint8_t {
|
||||
Disable = 0,
|
||||
Enable = 1,
|
||||
EnableWithHeight = 2,
|
||||
};
|
||||
|
||||
AP_Enum<GPSUse> _gps_use;
|
||||
AP_Int8 _gps_minsats;
|
||||
|
||||
private:
|
||||
|
||||
// these are experimentally derived from the simulator
|
||||
|
Loading…
Reference in New Issue
Block a user