mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 13:55:18 +03:00
Disable debug output.
This commit is contained in:
parent
b6a8e20d8c
commit
f5d9589f0a
2 changed files with 2 additions and 2 deletions
|
@ -132,7 +132,7 @@ void hcsr04_get_distance(volatile int32_t *distance)
|
||||||
last_measurement = current_time;
|
last_measurement = current_time;
|
||||||
distance_ptr = distance;
|
distance_ptr = distance;
|
||||||
|
|
||||||
#if 1
|
#if 0
|
||||||
debug[0] = *distance;
|
debug[0] = *distance;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -488,7 +488,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
|
||||||
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for altitude estimation (baro & acc)
|
accAlt = accAlt * barometerConfig->baro_cf_alt + (float)BaroAlt * (1.0f - barometerConfig->baro_cf_alt); // complementary filter for altitude estimation (baro & acc)
|
||||||
vel += vel_acc;
|
vel += vel_acc;
|
||||||
|
|
||||||
#if 1
|
#if 0
|
||||||
debug[1] = accSum[2] / accSumCount; // acceleration
|
debug[1] = accSum[2] / accSumCount; // acceleration
|
||||||
debug[2] = vel; // velocity
|
debug[2] = vel; // velocity
|
||||||
debug[3] = accAlt; // height
|
debug[3] = accAlt; // height
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue