mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: remove custom_rotation matrix to frontend
Only one of these per vehicle
This commit is contained in:
parent
645a5302d0
commit
d6c7c59199
@ -485,6 +485,11 @@ private:
|
|||||||
AP_Float _custom_pitch;
|
AP_Float _custom_pitch;
|
||||||
AP_Float _custom_yaw;
|
AP_Float _custom_yaw;
|
||||||
|
|
||||||
|
/*
|
||||||
|
* support for custom AHRS orientation, replacing _board_orientation
|
||||||
|
*/
|
||||||
|
Matrix3f _custom_rotation;
|
||||||
|
|
||||||
enum class EKFType {
|
enum class EKFType {
|
||||||
NONE = 0
|
NONE = 0
|
||||||
#if HAL_NAVEKF3_AVAILABLE
|
#if HAL_NAVEKF3_AVAILABLE
|
||||||
|
@ -430,8 +430,6 @@ protected:
|
|||||||
// multi-thread access support
|
// multi-thread access support
|
||||||
HAL_Semaphore _rsem;
|
HAL_Semaphore _rsem;
|
||||||
|
|
||||||
Matrix3f _custom_rotation;
|
|
||||||
|
|
||||||
// calculate sin/cos of roll/pitch/yaw from rotation
|
// calculate sin/cos of roll/pitch/yaw from rotation
|
||||||
void calc_trig(const Matrix3f &rot,
|
void calc_trig(const Matrix3f &rot,
|
||||||
float &cr, float &cp, float &cy,
|
float &cr, float &cp, float &cy,
|
||||||
|
Loading…
Reference in New Issue
Block a user