mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
Plane: changes for new AHRS API
This commit is contained in:
parent
04ba5fa0bd
commit
9adc879253
@ -1190,7 +1190,7 @@ const AP_Param::Info Plane::var_info[] PROGMEM = {
|
|||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
// @Group: EKF_
|
// @Group: EKF_
|
||||||
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
||||||
GOBJECTN(ahrs.get_NavEKF_const(), NavEKF, "EKF_", NavEKF),
|
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
AP_VAREND
|
AP_VAREND
|
||||||
|
@ -172,9 +172,22 @@ private:
|
|||||||
|
|
||||||
AP_InertialSensor ins;
|
AP_InertialSensor ins;
|
||||||
|
|
||||||
|
#if RANGEFINDER_ENABLED == ENABLED
|
||||||
|
// rangefinder
|
||||||
|
RangeFinder rangefinder;
|
||||||
|
|
||||||
|
struct {
|
||||||
|
bool in_range;
|
||||||
|
float correction;
|
||||||
|
uint32_t last_correction_time_ms;
|
||||||
|
uint8_t in_range_count;
|
||||||
|
} rangefinder_state;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Inertial Navigation EKF
|
// Inertial Navigation EKF
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder};
|
NavEKF EKF{&ahrs, barometer, rangefinder};
|
||||||
|
AP_AHRS_NavEKF ahrs {ins, barometer, gps, rangefinder, EKF};
|
||||||
#else
|
#else
|
||||||
AP_AHRS_DCM ahrs {ins, barometer, gps};
|
AP_AHRS_DCM ahrs {ins, barometer, gps};
|
||||||
#endif
|
#endif
|
||||||
@ -229,18 +242,6 @@ private:
|
|||||||
// a pin for reading the receiver RSSI voltage.
|
// a pin for reading the receiver RSSI voltage.
|
||||||
AP_HAL::AnalogSource *rssi_analog_source;
|
AP_HAL::AnalogSource *rssi_analog_source;
|
||||||
|
|
||||||
#if RANGEFINDER_ENABLED == ENABLED
|
|
||||||
// rangefinder
|
|
||||||
RangeFinder rangefinder;
|
|
||||||
|
|
||||||
struct {
|
|
||||||
bool in_range;
|
|
||||||
float correction;
|
|
||||||
uint32_t last_correction_time_ms;
|
|
||||||
uint8_t in_range_count;
|
|
||||||
} rangefinder_state;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Relay
|
// Relay
|
||||||
AP_Relay relay;
|
AP_Relay relay;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user