mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_OpticalFlow: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
a9b328e4de
commit
db5591a0ea
@ -14,6 +14,7 @@
|
|||||||
#include "AP_OpticalFlow_UPFLOW.h"
|
#include "AP_OpticalFlow_UPFLOW.h"
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
|
@ -22,6 +22,7 @@
|
|||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
|
#include <AP_AHRS/AP_AHRS.h>
|
||||||
|
|
||||||
const uint32_t AP_OPTICALFLOW_CAL_TIMEOUT_SEC = 120; // calibration timesout after 120 seconds
|
const uint32_t AP_OPTICALFLOW_CAL_TIMEOUT_SEC = 120; // calibration timesout after 120 seconds
|
||||||
const uint32_t AP_OPTICALFLOW_CAL_STATUSINTERVAL_SEC = 3; // status updates printed at 3 second intervals
|
const uint32_t AP_OPTICALFLOW_CAL_STATUSINTERVAL_SEC = 3; // status updates printed at 3 second intervals
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
#define AP_OPTICALFLOW_CAL_MAX_SAMPLES 50 // number of samples required before calibration begins
|
#define AP_OPTICALFLOW_CAL_MAX_SAMPLES 50 // number of samples required before calibration begins
|
||||||
|
|
||||||
@ -53,8 +54,10 @@ private:
|
|||||||
// calculate mean squared residual for all samples of a single axis (0 or 1) given a scalar parameter
|
// calculate mean squared residual for all samples of a single axis (0 or 1) given a scalar parameter
|
||||||
float calc_mean_squared_residuals(uint8_t axis, float scalar) const;
|
float calc_mean_squared_residuals(uint8_t axis, float scalar) const;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log a sample
|
// log a sample
|
||||||
void log_sample(uint8_t axis, uint8_t sample_num, float flow_rate, float body_rate, float los_pred);
|
void log_sample(uint8_t axis, uint8_t sample_num, float flow_rate, float body_rate, float los_pred);
|
||||||
|
#endif
|
||||||
|
|
||||||
// calibration states
|
// calibration states
|
||||||
enum class CalState {
|
enum class CalState {
|
||||||
|
Loading…
Reference in New Issue
Block a user