Browse Source

AP_AHRS: add set_posvelyaw_source_set

zr-v5.1
Randy Mackay 5 years ago
parent
commit
dc5d1d099b
  1. 3
      libraries/AP_AHRS/AP_AHRS.h
  2. 8
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  3. 3
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

3
libraries/AP_AHRS/AP_AHRS.h

@ -186,6 +186,9 @@ public: @@ -186,6 +186,9 @@ public:
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
virtual void request_yaw_reset(void) {}
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
virtual void set_posvelyaw_source_set(uint8_t source_set_idx) {}
// Euler angles (radians)
float roll;
float pitch;

8
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -2339,6 +2339,14 @@ void AP_AHRS_NavEKF::request_yaw_reset(void) @@ -2339,6 +2339,14 @@ void AP_AHRS_NavEKF::request_yaw_reset(void)
}
}
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
void AP_AHRS_NavEKF::set_posvelyaw_source_set(uint8_t source_set_idx)
{
#if HAL_NAVEKF3_AVAILABLE
EKF3.setPosVelYawSourceSet(source_set_idx);
#endif
}
void AP_AHRS_NavEKF::Log_Write()
{
#if HAL_NAVEKF2_AVAILABLE

3
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -299,6 +299,9 @@ public: @@ -299,6 +299,9 @@ public:
// request EKF yaw reset to try and avoid the need for an EKF lane switch or failsafe
void request_yaw_reset(void) override;
// set position, velocity and yaw sources to either 0=primary, 1=secondary, 2=tertiary
void set_posvelyaw_source_set(uint8_t source_set_idx) override;
void Log_Write();
// check whether external navigation is providing yaw. Allows compass pre-arm checks to be bypassed

Loading…
Cancel
Save