3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 38 for (uint8_t sensorIndex = 0; sensorIndex <= 1; sensorIndex++) {
40 if (sensor ==
nullptr) {
53 bool sampleFresh[2][3] = {};
54 for (uint8_t index = 0; index <= 2; index++) {
59 if (sampleFresh[sensorIndex][0] && sampleFresh[sensorIndex][1] && sampleFresh[sensorIndex][2]) {
194 if ((rawFlowQuality > 0) && rawFlowRates.
length() < 4.2f && rawGyroRates.
length() < 4.2f) {
260 for (uint8_t i=1; i<maxCount; i++) {
263 if (tempIndex >= maxCount) {
264 tempIndex -= maxCount;
290 if (changeDetected) {
475 float gps_delay_sec = 0;
653 const float baroDriftRate = 0.05f;
657 const float maxTerrGrad = 0.25f;
724 if (beacon ==
nullptr) {
732 bool newDataToPush =
false;
733 uint8_t numRngBcnsChecked = 0;
736 while (!newDataToPush && numRngBcnsChecked <
N_beacons) {
768 newDataToPush =
true;
785 if (posDiffSq < 9.0
f * posDiffVar) {
859 #endif // HAL_CPU_CLASS
float norm(const T first, const U second, const Params... parameters)
uint32_t last_update_ms(uint8_t i) const
AP_RangeFinder_Backend * get_backend(uint8_t id) const
gps_elements gpsDataDelayed
bool use_for_yaw(uint8_t i) const
return true if the compass should be used for yaw calculations
baro_elements baroDataDelayed
bool calcGpsGoodToAlign(void)
struct NavEKF3::@148 logging
void to_axis_angle(Vector3f &v)
uint32_t storedRngMeasTime_ms[2][3]
obs_ring_buffer_t< vel_odm_elements > storedBodyOdm
enum Rotation orientation() const
float beacon_distance(uint8_t beacon_instance) const
wheel_odm_elements wheelOdmDataNew
uint16_t distance_cm() const
uint32_t secondLastGpsTime_ms
imu_elements imuDataDelayed
bool setOriginLLH(const Location &loc)
float beaconVehiclePosErr
Interface definition for the various Ground Control System.
float storedRngMeas[2][3]
obs_ring_buffer_t< mag_elements > storedMag
void getTimingStatistics(struct ekf_timing &timing)
obs_ring_buffer_t< tas_elements > storedTAS
uint8_t lastRngBcnChecked
bool assume_zero_sideslip(void) const
void calcFiltBaroOffset()
uint8_t get_primary_gyro(void) const
uint32_t wheelOdmMeasTime_ms
void correctDeltaAngle(Vector3f &delAng, float delAngDT)
range_elements rangeDataNew
const uint16_t tasDelay_ms
uint32_t timeTasReceived_ms
uint32_t last_message_time_ms(uint8_t instance) const
void calcGpsGoodForFlight(void)
Quaternion imuQuatDownSampleNew
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
bool readDeltaAngle(uint8_t ins_index, Vector3f &dAng)
bool use_accel(uint8_t instance) const
tas_elements tasDataDelayed
const Location & location(uint8_t instance) const
uint32_t flowValidMeaTime_ms
AP_Float _visOdmVelErrMin
obs_ring_buffer_t< rng_bcn_elements > storedRangeBeacon
uint32_t framesSincePredict
baro_elements baroDataNew
const uint8_t flowTimeDeltaAvg_ms
bool beacon_healthy(uint8_t beacon_instance) const
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
struct NavEKF3_core::state_elements & stateStruct
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
const uint8_t sensorIntervalMin_ms
const Compass * get_compass() const
static AP_InertialSensor ins
bool use_compass(void) const
uint8_t localFilterTimeStep_ms
const AP_Airspeed * get_airspeed(void) const
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
uint8_t get_primary_accel(void) const
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
bool inhibitGpsVertVelUse
bool get_origin(Location &origin_loc) const
Vector3f beaconVehiclePosNED
output_elements outputDataNew
void updateTimingStatistics(void)
const Vector3f & velocity(uint8_t instance) const
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
bool use_gyro(uint8_t instance) const
bool speed_accuracy(uint8_t instance, float &sacc) const
bool get_vehicle_position_ned(Vector3f &pos, float &accuracy_estimate) const
float receiverPosCov[3][3]
uint32_t lastTimeGpsReceived_ms
obs_ring_buffer_t< gps_elements > storedGPS
const Vector3f & get_offsets(uint8_t i) const
float get_raw_airspeed(uint8_t i) const
Vector3f beacon_position(uint8_t beacon_instance) const
uint32_t lastRngMeasTime_ms
obs_ring_buffer_t< range_elements > storedRange
bool magStateResetRequest
uint64_t imuSampleTime_us
void rotation_matrix(Matrix3f &m) const
void detectOptFlowTakeoff(void)
void send_text(MAV_SEVERITY severity, const char *fmt,...)
const Vector3f & get_imu_pos_offset(uint8_t instance) const
AP_Float _visOdmVelErrMax
vel_odm_elements bodyOdmDataNew
GPS_Status status(uint8_t instance) const
Query GPS status.
imu_ring_buffer_t< imu_elements > storedIMU
uint32_t beacon_last_update_ms(uint8_t beacon_instance) const
void correctEkfOriginHeight()
uint8_t get_count(void) const
rng_bcn_elements rngBcnDataNew
obs_ring_buffer_t< of_elements > storedOF
struct NavEKF3_core::@154 gpsCheckStatus
float constrain_float(const float amt, const float low, const float high)
float get_EAS2TAS(uint8_t i) const
float get_altitude(void) const
const uint16_t magDelay_ms
void writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset, float radius)
uint8_t num_sats(uint8_t instance) const
uint32_t last_update_usec(void) const
float get_delta_angle_dt(uint8_t i) const
uint32_t lastMagUpdate_us
uint32_t lastOriginHgtTime_ms
float get_delta_velocity_dt(uint8_t i) const
obs_ring_buffer_t< wheel_odm_elements > storedWheelOdm
bool rngBcnAlignmentCompleted
uint32_t rngValidMeaTime_ms
uint8_t primary_sensor(void) const
uint32_t rngBcnLast3DmeasTime_ms
void writeOptFlowMeas(uint8_t &rawFlowQuality, Vector2f &rawFlowRates, Vector2f &rawGyroRates, uint32_t &msecFlowMeas, const Vector3f &posOffset)
void alignMagStateDeclination()
uint8_t get_gyro_count(void) const
const AP_Beacon * get_beacon(void) const
bool getTakeoffExpected()
AP_InertialSensor & ins()
void rotate(const Vector3f &v)
RangeFinder::RangeFinder_Status status() const
imu_elements imuDataDownSampledNew
Receiving valid messages and 3D lock.
uint32_t lastBaroReceived_ms
const Vector3f * body_offset
bool vertical_accuracy(uint8_t instance, float &vacc) const
bool readDeltaVelocity(uint8_t ins_index, Vector3f &dVel, float &dVel_dt)
struct Location EKF_origin
uint32_t bodyOdmMeasTime_ms
float get_loop_delta_t(void) const
int16_t ground_clearance_cm_orient(enum Rotation orientation) const
const Vector3f * hub_offset
void correctDeltaVelocity(Vector3f &delVel, float delVelDT)
bool horizontal_accuracy(uint8_t instance, float &hacc) const
obs_ring_buffer_t< baro_elements > storedBaro
rng_bcn_elements rngBcnDataDelayed
uint32_t imuSampleTime_ms
uint32_t get_last_update(void) const
uint32_t lastTimeRngBcn_ms[10]
uint32_t lastHealthyMagTime_ms
uint8_t get_accel_count(void) const
bool get_lag(uint8_t instance, float &lag_sec) const
bool have_vertical_velocity(uint8_t instance) const
const Vector3f * body_offset
void writeBodyFrameOdom(float quality, const Vector3f &delPos, const Vector3f &delAng, float delTime, uint32_t timeStamp_ms, const Vector3f &posOffset)